Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
amcl_node.cpp
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * This library is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public
7  * License as published by the Free Software Foundation; either
8  * version 2.1 of the License, or (at your option) any later version.
9  *
10  * This library is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  * Lesser General Public License for more details.
14  *
15  * You should have received a copy of the GNU Lesser General Public
16  * License along with this library; if not, write to the Free Software
17  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
18  *
19  */
20 
21 /* Author: Brian Gerkey */
22 
23 #include "nav2_amcl/amcl_node.hpp"
24 
25 #include <algorithm>
26 #include <memory>
27 #include <string>
28 #include <utility>
29 #include <vector>
30 
31 #include "nav2_amcl/angleutils.hpp"
32 #include "nav2_util/geometry_utils.hpp"
33 #include "nav2_amcl/pf/pf.hpp"
34 #include "nav2_util/string_utils.hpp"
35 #include "nav2_amcl/sensors/laser/laser.hpp"
36 #include "rclcpp/node_options.hpp"
37 #include "tf2/convert.hpp"
38 #include "tf2/utils.hpp"
39 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
40 #include "tf2/LinearMath/Transform.hpp"
41 #include "tf2_ros/buffer.hpp"
42 #include "tf2_ros/message_filter.hpp"
43 #include "tf2_ros/transform_broadcaster.hpp"
44 #include "tf2_ros/transform_listener.hpp"
45 #include "tf2_ros/create_timer_ros.hpp"
46 
47 #include "nav2_amcl/portable_utils.hpp"
48 #include "nav2_ros_common/validate_messages.hpp"
49 
50 using rcl_interfaces::msg::ParameterType;
51 using namespace std::chrono_literals;
52 
53 namespace nav2_amcl
54 {
55 using nav2_util::geometry_utils::orientationAroundZAxis;
56 
57 AmclNode::AmclNode(const rclcpp::NodeOptions & options)
58 : nav2::LifecycleNode("amcl", "", options)
59 {
60  RCLCPP_INFO(get_logger(), "Creating");
61 }
62 
63 AmclNode::~AmclNode()
64 {
65 }
66 
67 nav2::CallbackReturn
68 AmclNode::on_configure(const rclcpp_lifecycle::State & /*state*/)
69 {
70  RCLCPP_INFO(get_logger(), "Configuring");
71  callback_group_ = create_callback_group(
72  rclcpp::CallbackGroupType::MutuallyExclusive, false);
73  initParameters();
74  initTransforms();
75  initParticleFilter();
76  initLaserScan();
77  initMessageFilters();
78  initPubSub();
79  initServices();
80  initOdometry();
81  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
82  executor_->add_callback_group(callback_group_, get_node_base_interface());
83  executor_thread_ = std::make_unique<nav2::NodeThread>(executor_);
84  return nav2::CallbackReturn::SUCCESS;
85 }
86 
87 nav2::CallbackReturn
88 AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/)
89 {
90  RCLCPP_INFO(get_logger(), "Activating");
91 
92  // Lifecycle publishers must be explicitly activated
93  pose_pub_->on_activate();
94  particle_cloud_pub_->on_activate();
95 
96  first_pose_sent_ = false;
97 
98  // Keep track of whether we're in the active state. We won't
99  // process incoming callbacks until we are
100  active_ = true;
101 
102  if (set_initial_pose_) {
103  auto msg = std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>();
104 
105  msg->header.stamp = now();
106  msg->header.frame_id = global_frame_id_;
107  msg->pose.pose.position.x = initial_pose_x_;
108  msg->pose.pose.position.y = initial_pose_y_;
109  msg->pose.pose.position.z = initial_pose_z_;
110  msg->pose.pose.orientation = orientationAroundZAxis(initial_pose_yaw_);
111 
112  initialPoseReceived(msg);
113  } else if (init_pose_received_on_inactive) {
114  handleInitialPose(last_published_pose_);
115  }
116 
117  auto node = shared_from_this();
118  // Add callback for dynamic parameters
119  post_set_params_handler_ = node->add_post_set_parameters_callback(
120  std::bind(
121  &AmclNode::updateParametersCallback,
122  this, std::placeholders::_1));
123  on_set_params_handler_ = node->add_on_set_parameters_callback(
124  std::bind(
125  &AmclNode::validateParameterUpdatesCallback,
126  this, std::placeholders::_1));
127 
128  // create bond connection
129  createBond();
130 
131  return nav2::CallbackReturn::SUCCESS;
132 }
133 
134 nav2::CallbackReturn
135 AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
136 {
137  RCLCPP_INFO(get_logger(), "Deactivating");
138 
139  active_ = false;
140 
141  // Lifecycle publishers must be explicitly deactivated
142  pose_pub_->on_deactivate();
143  particle_cloud_pub_->on_deactivate();
144 
145  // shutdown and reset dynamic parameter handler
146  remove_post_set_parameters_callback(post_set_params_handler_.get());
147  post_set_params_handler_.reset();
148  remove_on_set_parameters_callback(on_set_params_handler_.get());
149  on_set_params_handler_.reset();
150 
151  // destroy bond connection
152  destroyBond();
153 
154  return nav2::CallbackReturn::SUCCESS;
155 }
156 
157 nav2::CallbackReturn
158 AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
159 {
160  RCLCPP_INFO(get_logger(), "Cleaning up");
161 
162  executor_thread_.reset();
163 
164  // Get rid of the inputs first (services and message filter input), so we
165  // don't continue to process incoming messages
166  global_loc_srv_.reset();
167  initial_guess_srv_.reset();
168  nomotion_update_srv_.reset();
169  initial_pose_sub_.reset();
170  laser_scan_connection_.disconnect();
171  tf_listener_.reset(); // listener may access lase_scan_filter_, so it should be reset earlier
172  laser_scan_filter_.reset();
173  laser_scan_sub_.reset();
174 
175  // Map
176  map_sub_.reset(); // map_sub_ may access map_, so it should be reset earlier
177  if (map_ != NULL) {
178  map_free(map_);
179  map_ = nullptr;
180  }
181  first_map_received_ = false;
182  free_space_indices.resize(0);
183 
184  // Transforms
185  tf_broadcaster_.reset();
186  tf_buffer_.reset();
187 
188  // PubSub
189  pose_pub_.reset();
190  particle_cloud_pub_.reset();
191 
192  // Odometry
193  motion_model_.reset();
194 
195  // Particle Filter
196  pf_free(pf_);
197  pf_ = nullptr;
198 
199  // Laser Scan
200  lasers_.clear();
201  lasers_update_.clear();
202  frame_to_laser_.clear();
203  force_update_ = true;
204 
205  if (set_initial_pose_) {
206  set_parameter(
207  rclcpp::Parameter(
208  "initial_pose.x",
209  rclcpp::ParameterValue(last_published_pose_.pose.pose.position.x)));
210  set_parameter(
211  rclcpp::Parameter(
212  "initial_pose.y",
213  rclcpp::ParameterValue(last_published_pose_.pose.pose.position.y)));
214  set_parameter(
215  rclcpp::Parameter(
216  "initial_pose.z",
217  rclcpp::ParameterValue(last_published_pose_.pose.pose.position.z)));
218  set_parameter(
219  rclcpp::Parameter(
220  "initial_pose.yaw",
221  rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation))));
222  }
223 
224  return nav2::CallbackReturn::SUCCESS;
225 }
226 
227 nav2::CallbackReturn
228 AmclNode::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
229 {
230  RCLCPP_INFO(get_logger(), "Shutting down");
231  return nav2::CallbackReturn::SUCCESS;
232 }
233 
234 bool
235 AmclNode::checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time)
236 {
237  rclcpp::Duration elapsed_time = now() - last_time;
238  if (elapsed_time.nanoseconds() * 1e-9 > check_interval.count()) {
239  return true;
240  }
241  return false;
242 }
243 
244 #if NEW_UNIFORM_SAMPLING
245 std::vector<AmclNode::Point2D> AmclNode::free_space_indices;
246 #endif
247 
248 bool
249 AmclNode::getOdomPose(
250  geometry_msgs::msg::PoseStamped & odom_pose,
251  double & x, double & y, double & yaw,
252  const rclcpp::Time & sensor_timestamp, const std::string & frame_id)
253 {
254  // Get the robot's pose
255  geometry_msgs::msg::PoseStamped ident;
256  ident.header.frame_id = frame_id;
257  ident.header.stamp = sensor_timestamp;
258  tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
259 
260  try {
261  tf_buffer_->transform(ident, odom_pose, odom_frame_id_);
262  } catch (tf2::TransformException & e) {
263  ++scan_error_count_;
264  if (scan_error_count_ % 20 == 0) {
265  RCLCPP_ERROR(
266  get_logger(), "(%d) consecutive laser scan transforms failed: (%s)", scan_error_count_,
267  e.what());
268  }
269  return false;
270  }
271 
272  scan_error_count_ = 0; // reset since we got a good transform
273  x = odom_pose.pose.position.x;
274  y = odom_pose.pose.position.y;
275  yaw = tf2::getYaw(odom_pose.pose.orientation);
276 
277  return true;
278 }
279 
281 AmclNode::uniformPoseGenerator(void * arg)
282 {
283  map_t * map = reinterpret_cast<map_t *>(arg);
284 
285 #if NEW_UNIFORM_SAMPLING
286  unsigned int rand_index = drand48() * free_space_indices.size();
287  AmclNode::Point2D free_point = free_space_indices[rand_index];
288  pf_vector_t p;
289  p.v[0] = MAP_WXGX(map, free_point.x);
290  p.v[1] = MAP_WYGY(map, free_point.y);
291  p.v[2] = drand48() * 2 * M_PI - M_PI;
292 #else
293  double min_x, max_x, min_y, max_y;
294 
295  min_x = (map->size_x * map->scale) / 2.0 - map->origin_x;
296  max_x = (map->size_x * map->scale) / 2.0 + map->origin_x;
297  min_y = (map->size_y * map->scale) / 2.0 - map->origin_y;
298  max_y = (map->size_y * map->scale) / 2.0 + map->origin_y;
299 
300  pf_vector_t p;
301 
302  RCLCPP_DEBUG(get_logger(), "Generating new uniform sample");
303  for (;; ) {
304  p.v[0] = min_x + drand48() * (max_x - min_x);
305  p.v[1] = min_y + drand48() * (max_y - min_y);
306  p.v[2] = drand48() * 2 * M_PI - M_PI;
307  // Check that it's a free cell
308  int i, j;
309  i = MAP_GXWX(map, p.v[0]);
310  j = MAP_GYWY(map, p.v[1]);
311  if (MAP_VALID(map, i, j) && (map->cells[MAP_INDEX(map, i, j)].occ_state == -1)) {
312  break;
313  }
314  }
315 #endif
316  return p;
317 }
318 
319 void
320 AmclNode::globalLocalizationCallback(
321  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
322  const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
323  std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
324 {
325  std::lock_guard<std::recursive_mutex> cfl(mutex_);
326 
327  RCLCPP_INFO(get_logger(), "Initializing with uniform distribution");
328 
329  pf_init_model(
330  pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
331  reinterpret_cast<void *>(map_));
332  RCLCPP_INFO(get_logger(), "Global initialisation done!");
333  initial_pose_is_known_ = true;
334  pf_init_ = false;
335 }
336 
337 void
338 AmclNode::initialPoseReceivedSrv(
339  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
340  const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
341  std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>/*res*/)
342 {
343  initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
344 }
345 
346 // force nomotion updates (amcl updating without requiring motion)
347 void
348 AmclNode::nomotionUpdateCallback(
349  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
350  const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
351  std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
352 {
353  RCLCPP_INFO(get_logger(), "Requesting no-motion update");
354  force_update_ = true;
355 }
356 
357 void
358 AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
359 {
360  std::lock_guard<std::recursive_mutex> cfl(mutex_);
361 
362  RCLCPP_INFO(get_logger(), "initialPoseReceived");
363 
364  if (!nav2::validateMsg(*msg)) {
365  RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting.");
366  return;
367  }
368  if (msg->header.frame_id != global_frame_id_) {
369  RCLCPP_WARN(
370  get_logger(),
371  "Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
372  msg->header.frame_id.c_str(),
373  global_frame_id_.c_str());
374  return;
375  }
376  if (first_map_received_ && (abs(msg->pose.pose.position.x) > map_->size_x ||
377  abs(msg->pose.pose.position.y) > map_->size_y))
378  {
379  RCLCPP_ERROR(
380  get_logger(), "Received initialpose from message is out of the size of map. Rejecting.");
381  return;
382  }
383 
384  // Overriding last published pose to initial pose
385  last_published_pose_ = *msg;
386 
387  if (!active_) {
388  init_pose_received_on_inactive = true;
389  RCLCPP_WARN(
390  get_logger(), "Received initial pose request, "
391  "but AMCL is not yet in the active state");
392  return;
393  }
394  handleInitialPose(*msg);
395 }
396 
397 void
398 AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
399 {
400  std::lock_guard<std::recursive_mutex> cfl(mutex_);
401  // In case the client sent us a pose estimate in the past, integrate the
402  // intervening odometric change.
403  geometry_msgs::msg::TransformStamped tx_odom;
404  try {
405  rclcpp::Time rclcpp_time = now();
406  tf2::TimePoint tf2_time(std::chrono::nanoseconds(rclcpp_time.nanoseconds()));
407 
408  // Check if the transform is available
409  tx_odom = tf_buffer_->lookupTransform(
410  base_frame_id_, tf2_ros::fromMsg(msg.header.stamp),
411  base_frame_id_, tf2_time, odom_frame_id_);
412  } catch (tf2::TransformException & e) {
413  // If we've never sent a transform, then this is normal, because the
414  // global_frame_id_ frame doesn't exist. We only care about in-time
415  // transformation for on-the-move pose-setting, so ignoring this
416  // startup condition doesn't really cost us anything.
417  if (sent_first_transform_) {
418  RCLCPP_WARN(get_logger(), "Failed to transform initial pose in time (%s)", e.what());
419  }
420  tf2::impl::Converter<false, true>::convert(tf2::Transform::getIdentity(), tx_odom.transform);
421  }
422 
423  tf2::Transform tx_odom_tf2;
424  tf2::impl::Converter<true, false>::convert(tx_odom.transform, tx_odom_tf2);
425 
426  tf2::Transform pose_old;
427  tf2::impl::Converter<true, false>::convert(msg.pose.pose, pose_old);
428 
429  tf2::Transform pose_new = pose_old * tx_odom_tf2;
430 
431  // Transform into the global frame
432 
433  RCLCPP_INFO(
434  get_logger(), "Setting pose (%.6f): %.3f %.3f %.3f",
435  now().nanoseconds() * 1e-9,
436  pose_new.getOrigin().x(),
437  pose_new.getOrigin().y(),
438  tf2::getYaw(pose_new.getRotation()));
439 
440  // Re-initialize the filter
441  pf_vector_t pf_init_pose_mean = pf_vector_zero();
442  pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
443  pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
444  pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
445 
446  pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
447  // Copy in the covariance, converting from 6-D to 3-D
448  for (int i = 0; i < 2; i++) {
449  for (int j = 0; j < 2; j++) {
450  pf_init_pose_cov.m[i][j] = msg.pose.covariance[6 * i + j];
451  }
452  }
453 
454  pf_init_pose_cov.m[2][2] = msg.pose.covariance[6 * 5 + 5];
455 
456  pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
457  pf_init_ = false;
458  init_pose_received_on_inactive = false;
459  initial_pose_is_known_ = true;
460 }
461 
462 void
463 AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
464 {
465  std::lock_guard<std::recursive_mutex> cfl(mutex_);
466 
467  // Since the sensor data is continually being published by the simulator or robot,
468  // we don't want our callbacks to fire until we're in the active state
469  if (!active_) {return;}
470  if (!first_map_received_) {
471  if (checkElapsedTime(2s, last_time_printed_msg_)) {
472  RCLCPP_WARN(get_logger(), "Waiting for map....");
473  last_time_printed_msg_ = now();
474  }
475  return;
476  }
477 
478  std::string laser_scan_frame_id = laser_scan->header.frame_id;
479  last_laser_received_ts_ = now();
480  int laser_index = -1;
481  geometry_msgs::msg::PoseStamped laser_pose;
482 
483  // Do we have the base->base_laser Tx yet?
484  if (frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) {
485  if (!addNewScanner(laser_index, laser_scan, laser_scan_frame_id, laser_pose)) {
486  return; // could not find transform
487  }
488  } else {
489  // we have the laser pose, retrieve laser index
490  laser_index = frame_to_laser_[laser_scan->header.frame_id];
491  }
492 
493  // Where was the robot when this scan was taken?
494  pf_vector_t pose;
495  if (!getOdomPose(
496  latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
497  laser_scan->header.stamp, base_frame_id_))
498  {
499  RCLCPP_ERROR(get_logger(), "Couldn't determine robot's pose associated with laser scan");
500  return;
501  }
502 
503  pf_vector_t delta = pf_vector_zero();
504  bool force_publication = false;
505  if (!pf_init_) {
506  // Pose at last filter update
507  pf_odom_pose_ = pose;
508  pf_init_ = true;
509 
510  for (unsigned int i = 0; i < lasers_update_.size(); i++) {
511  lasers_update_[i] = true;
512  }
513 
514  force_publication = true;
515  resample_count_ = 0;
516  } else {
517  // Set the laser update flags
518  if (shouldUpdateFilter(pose, delta)) {
519  for (unsigned int i = 0; i < lasers_update_.size(); i++) {
520  lasers_update_[i] = true;
521  }
522  }
523  if (lasers_update_[laser_index]) {
524  motion_model_->odometryUpdate(pf_, pose, delta);
525  }
526  force_update_ = false;
527  }
528 
529  bool resampled = false;
530 
531  // If the robot has moved, update the filter
532  if (lasers_update_[laser_index]) {
533  updateFilter(laser_index, laser_scan, pose);
534 
535  // Resample the particles
536  if (!(++resample_count_ % resample_interval_)) {
537  pf_update_resample(pf_, reinterpret_cast<void *>(map_));
538  resampled = true;
539  }
540 
541  pf_sample_set_t * set = pf_->sets + pf_->current_set;
542  RCLCPP_DEBUG(get_logger(), "Num samples: %d\n", set->sample_count);
543 
544  if (!force_update_) {
545  publishParticleCloud(set);
546  }
547  }
548  if (resampled || force_publication || !first_pose_sent_) {
549  amcl_hyp_t max_weight_hyps;
550  std::vector<amcl_hyp_t> hyps;
551  int max_weight_hyp = -1;
552  if (getMaxWeightHyp(hyps, max_weight_hyps, max_weight_hyp)) {
553  publishAmclPose(laser_scan, hyps, max_weight_hyp);
554  calculateMaptoOdomTransform(laser_scan, hyps, max_weight_hyp);
555 
556  if (tf_broadcast_ == true) {
557  // We want to send a transform that is good up until a
558  // tolerance time so that odom can be used
559  auto stamp = tf2_ros::fromMsg(laser_scan->header.stamp);
560  tf2::TimePoint transform_expiration = stamp + transform_tolerance_;
561  sendMapToOdomTransform(transform_expiration);
562  sent_first_transform_ = true;
563  }
564  } else {
565  RCLCPP_ERROR(get_logger(), "No pose!");
566  }
567  } else if (latest_tf_valid_) {
568  if (tf_broadcast_ == true) {
569  // Nothing changed, so we'll just republish the last transform, to keep
570  // everybody happy.
571  tf2::TimePoint transform_expiration = tf2_ros::fromMsg(laser_scan->header.stamp) +
572  transform_tolerance_;
573  sendMapToOdomTransform(transform_expiration);
574  }
575  }
576 }
577 
578 bool AmclNode::addNewScanner(
579  int & laser_index,
580  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
581  const std::string & laser_scan_frame_id,
582  geometry_msgs::msg::PoseStamped & laser_pose)
583 {
584  lasers_.push_back(createLaserObject());
585  lasers_update_.push_back(true);
586  laser_index = frame_to_laser_.size();
587 
588  geometry_msgs::msg::PoseStamped ident;
589  ident.header.frame_id = laser_scan_frame_id;
590  ident.header.stamp = rclcpp::Time();
591  tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
592  try {
593  tf_buffer_->transform(ident, laser_pose, base_frame_id_, transform_tolerance_);
594  } catch (tf2::TransformException & e) {
595  RCLCPP_ERROR(
596  get_logger(), "Couldn't transform from %s to %s, "
597  "even though the message notifier is in use: (%s)",
598  laser_scan->header.frame_id.c_str(),
599  base_frame_id_.c_str(), e.what());
600  return false;
601  }
602 
603  pf_vector_t laser_pose_v;
604  laser_pose_v.v[0] = laser_pose.pose.position.x;
605  laser_pose_v.v[1] = laser_pose.pose.position.y;
606  // laser mounting angle gets computed later -> set to 0 here!
607  laser_pose_v.v[2] = 0;
608  lasers_[laser_index]->SetLaserPose(laser_pose_v);
609  frame_to_laser_[laser_scan->header.frame_id] = laser_index;
610  return true;
611 }
612 
613 bool AmclNode::shouldUpdateFilter(const pf_vector_t pose, pf_vector_t & delta)
614 {
615  delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
616  delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
617  delta.v[2] = angleutils::angle_diff(pose.v[2], pf_odom_pose_.v[2]);
618 
619  // See if we should update the filter
620  bool update = fabs(delta.v[0]) > d_thresh_ ||
621  fabs(delta.v[1]) > d_thresh_ ||
622  fabs(delta.v[2]) > a_thresh_;
623  update = update || force_update_;
624  return update;
625 }
626 
627 bool AmclNode::updateFilter(
628  const int & laser_index,
629  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
630  const pf_vector_t & pose)
631 {
632  nav2_amcl::LaserData ldata;
633  ldata.laser = lasers_[laser_index];
634  ldata.range_count = laser_scan->ranges.size();
635  // To account for lasers that are mounted upside-down, we determine the
636  // min, max, and increment angles of the laser in the base frame.
637  //
638  // Construct min and max angles of laser, in the base_link frame.
639  // Here we set the roll pitch yaw of the lasers. We assume roll and pitch are zero.
640  geometry_msgs::msg::QuaternionStamped min_q, inc_q;
641  min_q.header.stamp = laser_scan->header.stamp;
642  min_q.header.frame_id = laser_scan->header.frame_id;
643  min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min);
644 
645  inc_q.header = min_q.header;
646  inc_q.quaternion = orientationAroundZAxis(laser_scan->angle_min + laser_scan->angle_increment);
647  try {
648  tf_buffer_->transform(min_q, min_q, base_frame_id_);
649  tf_buffer_->transform(inc_q, inc_q, base_frame_id_);
650  } catch (tf2::TransformException & e) {
651  RCLCPP_WARN(
652  get_logger(), "Unable to transform min/max laser angles into base frame: %s",
653  e.what());
654  return false;
655  }
656  double angle_min = tf2::getYaw(min_q.quaternion);
657  double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
658 
659  // wrapping angle to [-pi .. pi]
660  angle_increment = fmod(angle_increment + 5 * M_PI, 2 * M_PI) - M_PI;
661 
662  RCLCPP_DEBUG(
663  get_logger(), "Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
664  angle_increment);
665 
666  // Check the validity of range_max, must > 0.0
667  if (laser_scan->range_max <= 0.0) {
668  RCLCPP_WARN(
669  get_logger(), "wrong range_max of laser_scan data: %f. The message could be malformed."
670  " Ignore this message and stop updating.",
671  laser_scan->range_max);
672  return false;
673  }
674 
675  // Apply range min/max thresholds, if the user supplied them
676  if (laser_max_range_ > 0.0) {
677  ldata.range_max = std::min(laser_scan->range_max, static_cast<float>(laser_max_range_));
678  } else {
679  ldata.range_max = laser_scan->range_max;
680  }
681  double range_min;
682  if (laser_min_range_ > 0.0) {
683  range_min = std::max(laser_scan->range_min, static_cast<float>(laser_min_range_));
684  } else {
685  range_min = laser_scan->range_min;
686  }
687 
688  // The LaserData destructor will free this memory
689  ldata.ranges = new double[ldata.range_count][2];
690  for (int i = 0; i < ldata.range_count; i++) {
691  // amcl doesn't (yet) have a concept of min range. So we'll map short
692  // readings to max range.
693  if (laser_scan->ranges[i] <= range_min) {
694  ldata.ranges[i][0] = ldata.range_max;
695  } else {
696  ldata.ranges[i][0] = laser_scan->ranges[i];
697  }
698  // Compute bearing
699  ldata.ranges[i][1] = angle_min +
700  (i * angle_increment);
701  }
702  lasers_[laser_index]->sensorUpdate(pf_, reinterpret_cast<nav2_amcl::LaserData *>(&ldata));
703  lasers_update_[laser_index] = false;
704  pf_odom_pose_ = pose;
705  return true;
706 }
707 
708 void
709 AmclNode::publishParticleCloud(const pf_sample_set_t * set)
710 {
711  // If initial pose is not known, AMCL does not know the current pose
712  if (!initial_pose_is_known_) {return;}
713  auto cloud_with_weights_msg = std::make_unique<nav2_msgs::msg::ParticleCloud>();
714  cloud_with_weights_msg->header.stamp = this->now();
715  cloud_with_weights_msg->header.frame_id = global_frame_id_;
716  cloud_with_weights_msg->particles.resize(set->sample_count);
717 
718  for (int i = 0; i < set->sample_count; i++) {
719  cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
720  cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
721  cloud_with_weights_msg->particles[i].pose.position.z = 0;
722  cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
723  set->samples[i].pose.v[2]);
724  cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
725  }
726 
727  particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
728 }
729 
730 bool
731 AmclNode::getMaxWeightHyp(
732  std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
733  int & max_weight_hyp)
734 {
735  // Read out the current hypotheses
736  double max_weight = 0.0;
737  hyps.resize(pf_->sets[pf_->current_set].cluster_count);
738  for (int hyp_count = 0;
739  hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
740  {
741  double weight;
742  pf_vector_t pose_mean;
743  pf_matrix_t pose_cov;
744  if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) {
745  RCLCPP_ERROR(get_logger(), "Couldn't get stats on cluster %d", hyp_count);
746  return false;
747  }
748 
749  hyps[hyp_count].weight = weight;
750  hyps[hyp_count].pf_pose_mean = pose_mean;
751  hyps[hyp_count].pf_pose_cov = pose_cov;
752 
753  if (hyps[hyp_count].weight > max_weight) {
754  max_weight = hyps[hyp_count].weight;
755  max_weight_hyp = hyp_count;
756  }
757  }
758 
759  if (max_weight > 0.0) {
760  RCLCPP_DEBUG(
761  get_logger(), "Max weight pose: %.3f %.3f %.3f",
762  hyps[max_weight_hyp].pf_pose_mean.v[0],
763  hyps[max_weight_hyp].pf_pose_mean.v[1],
764  hyps[max_weight_hyp].pf_pose_mean.v[2]);
765 
766  max_weight_hyps = hyps[max_weight_hyp];
767  return true;
768  }
769  return false;
770 }
771 
772 void
773 AmclNode::publishAmclPose(
774  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
775  const std::vector<amcl_hyp_t> & hyps, const int & max_weight_hyp)
776 {
777  // If initial pose is not known, AMCL does not know the current pose
778  if (!initial_pose_is_known_) {
779  if (checkElapsedTime(2s, last_time_printed_msg_)) {
780  RCLCPP_WARN(
781  get_logger(), "AMCL cannot publish a pose or update the transform. "
782  "Please set the initial pose...");
783  last_time_printed_msg_ = now();
784  }
785  return;
786  }
787 
788  auto p = std::make_unique<geometry_msgs::msg::PoseWithCovarianceStamped>();
789  // Fill in the header
790  p->header.frame_id = global_frame_id_;
791  p->header.stamp = laser_scan->header.stamp;
792  // Copy in the pose
793  p->pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
794  p->pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
795  p->pose.pose.orientation = orientationAroundZAxis(hyps[max_weight_hyp].pf_pose_mean.v[2]);
796  // Copy in the covariance, converting from 3-D to 6-D
797  pf_sample_set_t * set = pf_->sets + pf_->current_set;
798  for (int i = 0; i < 2; i++) {
799  for (int j = 0; j < 2; j++) {
800  // Report the overall filter covariance, rather than the
801  // covariance for the highest-weight cluster
802  // p->covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j];
803  p->pose.covariance[6 * i + j] = set->cov.m[i][j];
804  }
805  }
806  p->pose.covariance[6 * 5 + 5] = set->cov.m[2][2];
807  float temp = 0.0;
808  for (auto covariance_value : p->pose.covariance) {
809  temp += covariance_value;
810  }
811  temp += p->pose.pose.position.x + p->pose.pose.position.y;
812  if (!std::isnan(temp)) {
813  RCLCPP_DEBUG(get_logger(), "Publishing pose");
814  last_published_pose_ = *p;
815  first_pose_sent_ = true;
816  pose_pub_->publish(std::move(p));
817  } else {
818  RCLCPP_WARN(
819  get_logger(), "AMCL covariance or pose is NaN, likely due to an invalid "
820  "configuration or faulty sensor measurements! Pose is not available!");
821  }
822 
823  RCLCPP_DEBUG(
824  get_logger(), "New pose: %6.3f %6.3f %6.3f",
825  hyps[max_weight_hyp].pf_pose_mean.v[0],
826  hyps[max_weight_hyp].pf_pose_mean.v[1],
827  hyps[max_weight_hyp].pf_pose_mean.v[2]);
828 }
829 
830 void
831 AmclNode::calculateMaptoOdomTransform(
832  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
833  const std::vector<amcl_hyp_t> & hyps, const int & max_weight_hyp)
834 {
835  // subtracting base to odom from map to base and send map to odom instead
836  geometry_msgs::msg::PoseStamped odom_to_map;
837  try {
838  tf2::Quaternion q;
839  q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
840  tf2::Transform tmp_tf(q, tf2::Vector3(
841  hyps[max_weight_hyp].pf_pose_mean.v[0],
842  hyps[max_weight_hyp].pf_pose_mean.v[1],
843  0.0));
844 
845  geometry_msgs::msg::PoseStamped tmp_tf_stamped;
846  tmp_tf_stamped.header.frame_id = base_frame_id_;
847  tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
848  tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose);
849 
850  tf_buffer_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_);
851  } catch (tf2::TransformException & e) {
852  RCLCPP_DEBUG(get_logger(), "Failed to subtract base to odom transform: (%s)", e.what());
853  return;
854  }
855 
856  tf2::impl::Converter<true, false>::convert(odom_to_map.pose, latest_tf_);
857  latest_tf_valid_ = true;
858 }
859 
860 void
861 AmclNode::sendMapToOdomTransform(const tf2::TimePoint & transform_expiration)
862 {
863  // AMCL will update transform only when it has knowledge about robot's initial position
864  if (!initial_pose_is_known_) {return;}
865  geometry_msgs::msg::TransformStamped tmp_tf_stamped;
866  tmp_tf_stamped.header.frame_id = global_frame_id_;
867  tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_expiration);
868  tmp_tf_stamped.child_frame_id = odom_frame_id_;
869  tf2::impl::Converter<false, true>::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
870  tf_broadcaster_->sendTransform(tmp_tf_stamped);
871 }
872 
874 AmclNode::createLaserObject()
875 {
876  RCLCPP_INFO(get_logger(), "createLaserObject");
877 
878  if (sensor_model_type_ == "beam") {
879  return new nav2_amcl::BeamModel(
880  z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_,
881  0.0, max_beams_, map_);
882  }
883 
884  if (sensor_model_type_ == "likelihood_field_prob") {
886  z_hit_, z_rand_, sigma_hit_,
887  laser_likelihood_max_dist_, do_beamskip_, beam_skip_distance_, beam_skip_threshold_,
888  beam_skip_error_threshold_, max_beams_, map_);
889  }
890 
892  z_hit_, z_rand_, sigma_hit_,
893  laser_likelihood_max_dist_, max_beams_, map_);
894 }
895 
896 void
897 AmclNode::initParameters()
898 {
899  double save_pose_rate;
900  double tmp_tol;
901 
902  alpha1_ = this->declare_or_get_parameter("alpha1", 0.2);
903  alpha2_ = this->declare_or_get_parameter("alpha2", 0.2);
904  alpha3_ = this->declare_or_get_parameter("alpha3", 0.2);
905  alpha4_ = this->declare_or_get_parameter("alpha4", 0.2);
906  alpha5_ = this->declare_or_get_parameter("alpha5", 0.2);
907  base_frame_id_ = this->declare_or_get_parameter("base_frame_id", std::string{"base_footprint"});
908  beam_skip_distance_ = this->declare_or_get_parameter("beam_skip_distance", 0.5);
909  beam_skip_error_threshold_ = this->declare_or_get_parameter("beam_skip_error_threshold", 0.9);
910  beam_skip_threshold_ = this->declare_or_get_parameter("beam_skip_threshold", 0.3);
911  do_beamskip_ = this->declare_or_get_parameter("do_beamskip", false);
912  global_frame_id_ = this->declare_or_get_parameter("global_frame_id", std::string{"map"});
913  lambda_short_ = this->declare_or_get_parameter("lambda_short", 0.1);
914  laser_likelihood_max_dist_ = this->declare_or_get_parameter("laser_likelihood_max_dist", 2.0);
915  laser_max_range_ = this->declare_or_get_parameter("laser_max_range", 100.0);
916  laser_min_range_ = this->declare_or_get_parameter("laser_min_range", -1.0);
917  sensor_model_type_ = this->declare_or_get_parameter(
918  "laser_model_type", std::string{"likelihood_field"});
919  set_initial_pose_ = this->declare_or_get_parameter("set_initial_pose", false);
920  initial_pose_x_ = this->declare_or_get_parameter("initial_pose.x", 0.0);
921  initial_pose_y_ = this->declare_or_get_parameter("initial_pose.y", 0.0);
922  initial_pose_z_ = this->declare_or_get_parameter("initial_pose.z", 0.0);
923  initial_pose_yaw_ = this->declare_or_get_parameter("initial_pose.yaw", 0.0);
924  max_beams_ = this->declare_or_get_parameter("max_beams", 60);
925  max_particles_ = this->declare_or_get_parameter("max_particles", 2000);
926  min_particles_ = this->declare_or_get_parameter("min_particles", 500);
927  odom_frame_id_ = this->declare_or_get_parameter("odom_frame_id", std::string{"odom"});
928  pf_err_ = this->declare_or_get_parameter("pf_err", 0.05);
929  pf_z_ = this->declare_or_get_parameter("pf_z", 0.99);
930  alpha_fast_ = this->declare_or_get_parameter("recovery_alpha_fast", 0.0);
931  alpha_slow_ = this->declare_or_get_parameter("recovery_alpha_slow", 0.0);
932  resample_interval_ = this->declare_or_get_parameter("resample_interval", 1);
933  robot_model_type_ = this->declare_or_get_parameter(
934  "robot_model_type", std::string{"nav2_amcl::DifferentialMotionModel"});
935  save_pose_rate = this->declare_or_get_parameter("save_pose_rate", 0.5);
936  sigma_hit_ = this->declare_or_get_parameter("sigma_hit", 0.2);
937  tf_broadcast_ = this->declare_or_get_parameter("tf_broadcast", true);
938  tmp_tol = this->declare_or_get_parameter("transform_tolerance", 1.0);
939  a_thresh_ = this->declare_or_get_parameter("update_min_a", 0.2);
940  d_thresh_ = this->declare_or_get_parameter("update_min_d", 0.25);
941  z_hit_ = this->declare_or_get_parameter("z_hit", 0.5);
942  z_max_ = this->declare_or_get_parameter("z_max", 0.05);
943  z_rand_ = this->declare_or_get_parameter("z_rand", 0.5);
944  z_short_ = this->declare_or_get_parameter("z_short", 0.05);
945  first_map_only_ = this->declare_or_get_parameter("first_map_only", false);
946  always_reset_initial_pose_ = this->declare_or_get_parameter("always_reset_initial_pose", false);
947  scan_topic_ = this->declare_or_get_parameter("scan_topic", std::string{"scan"});
948  map_topic_ = this->declare_or_get_parameter("map_topic", std::string{"map"});
949  freespace_downsampling_ = this->declare_or_get_parameter("freespace_downsampling", false);
950 
951  save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
952  transform_tolerance_ = tf2::durationFromSec(tmp_tol);
953  last_time_printed_msg_ = now();
954 
955  // Semantic checks
956  if (laser_likelihood_max_dist_ < 0) {
957  RCLCPP_WARN(
958  get_logger(), "You've set laser_likelihood_max_dist to be negative,"
959  " this isn't allowed so it will be set to default value 2.0.");
960  laser_likelihood_max_dist_ = 2.0;
961  }
962  if (max_particles_ < 0) {
963  RCLCPP_WARN(
964  get_logger(), "You've set max_particles to be negative,"
965  " this isn't allowed so it will be set to default value 2000.");
966  max_particles_ = 2000;
967  }
968 
969  if (min_particles_ < 0) {
970  RCLCPP_WARN(
971  get_logger(), "You've set min_particles to be negative,"
972  " this isn't allowed so it will be set to default value 500.");
973  min_particles_ = 500;
974  }
975 
976  if (min_particles_ > max_particles_) {
977  RCLCPP_WARN(
978  get_logger(), "You've set min_particles to be greater than max particles,"
979  " this isn't allowed so max_particles will be set to min_particles.");
980  max_particles_ = min_particles_;
981  }
982 
983  if (resample_interval_ <= 0) {
984  RCLCPP_WARN(
985  get_logger(), "You've set resample_interval to be zero or negative,"
986  " this isn't allowed so it will be set to default value to 1.");
987  resample_interval_ = 1;
988  }
989 
990  if (always_reset_initial_pose_) {
991  initial_pose_is_known_ = false;
992  }
993 }
994 
995 rcl_interfaces::msg::SetParametersResult AmclNode::validateParameterUpdatesCallback(
996  std::vector<rclcpp::Parameter> parameters)
997 {
998  rcl_interfaces::msg::SetParametersResult result;
999  result.successful = true;
1000  for (auto parameter : parameters) {
1001  const auto & param_type = parameter.get_type();
1002  const auto & param_name = parameter.get_name();
1003  if (param_name.find('.') != std::string::npos) {
1004  continue;
1005  }
1006  if (param_type == ParameterType::PARAMETER_DOUBLE) {
1007  if (parameter.as_double() < 0.0 &&
1008  (param_name != "laser_min_range" || param_name != "laser_max_range"))
1009  {
1010  RCLCPP_WARN(
1011  get_logger(), "The value of parameter '%s' is incorrectly set to %f, "
1012  "it should be >=0. Ignoring parameter update.",
1013  param_name.c_str(), parameter.as_double());
1014  result.successful = false;
1015  }
1016  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
1017  if (parameter.as_int() <= 0.0 && param_name == "resample_interval") {
1018  RCLCPP_WARN(
1019  get_logger(), "The value of resample_interval is incorrectly set, "
1020  "it should be >0. Ignoring parameter update.");
1021  result.successful = false;
1022  } else if (parameter.as_int() < 0.0) {
1023  RCLCPP_WARN(
1024  get_logger(), "The value of parameter '%s' is incorrectly set to %ld, "
1025  "it should be >=0. Ignoring parameter update.",
1026  param_name.c_str(), parameter.as_int());
1027  result.successful = false;
1028  } else if (param_name == "max_particles" && parameter.as_int() < min_particles_) {
1029  RCLCPP_WARN(
1030  get_logger(), "The value of max_particles is incorrectly set, "
1031  "it should be larger than min_particles. Ignoring parameter update.");
1032  result.successful = false;
1033  } else if (param_name == "min_particles" && parameter.as_int() > max_particles_) {
1034  RCLCPP_WARN(
1035  get_logger(), "The value of min_particles is incorrectly set, "
1036  "it should be smaller than max particles. Ignoring parameter update.");
1037  result.successful = false;
1038  }
1039  }
1040  }
1041  return result;
1042 }
1043 
1044 void
1045 AmclNode::updateParametersCallback(
1046  std::vector<rclcpp::Parameter> parameters)
1047 {
1048  std::lock_guard<std::recursive_mutex> cfl(mutex_);
1049 
1050  bool reinit_pf = false;
1051  bool reinit_odom = false;
1052  bool reinit_laser = false;
1053  bool reinit_map = false;
1054 
1055  for (const auto & parameter : parameters) {
1056  const auto & param_type = parameter.get_type();
1057  const auto & param_name = parameter.get_name();
1058  if (param_name.find('.') != std::string::npos) {
1059  continue;
1060  }
1061  if (param_type == ParameterType::PARAMETER_DOUBLE) {
1062  if (param_name == "alpha1") {
1063  alpha1_ = parameter.as_double();
1064  reinit_odom = true;
1065  } else if (param_name == "alpha2") {
1066  alpha2_ = parameter.as_double();
1067  reinit_odom = true;
1068  } else if (param_name == "alpha3") {
1069  alpha3_ = parameter.as_double();
1070  reinit_odom = true;
1071  } else if (param_name == "alpha4") {
1072  alpha4_ = parameter.as_double();
1073  reinit_odom = true;
1074  } else if (param_name == "alpha5") {
1075  alpha5_ = parameter.as_double();
1076  reinit_odom = true;
1077  } else if (param_name == "beam_skip_distance") {
1078  beam_skip_distance_ = parameter.as_double();
1079  reinit_laser = true;
1080  } else if (param_name == "beam_skip_error_threshold") {
1081  beam_skip_error_threshold_ = parameter.as_double();
1082  reinit_laser = true;
1083  } else if (param_name == "beam_skip_threshold") {
1084  beam_skip_threshold_ = parameter.as_double();
1085  reinit_laser = true;
1086  } else if (param_name == "lambda_short") {
1087  lambda_short_ = parameter.as_double();
1088  reinit_laser = true;
1089  } else if (param_name == "laser_likelihood_max_dist") {
1090  laser_likelihood_max_dist_ = parameter.as_double();
1091  reinit_laser = true;
1092  } else if (param_name == "laser_max_range") {
1093  laser_max_range_ = parameter.as_double();
1094  reinit_laser = true;
1095  } else if (param_name == "laser_min_range") {
1096  laser_min_range_ = parameter.as_double();
1097  reinit_laser = true;
1098  } else if (param_name == "pf_err") {
1099  pf_err_ = parameter.as_double();
1100  reinit_pf = true;
1101  } else if (param_name == "pf_z") {
1102  pf_z_ = parameter.as_double();
1103  reinit_pf = true;
1104  } else if (param_name == "recovery_alpha_fast") {
1105  alpha_fast_ = parameter.as_double();
1106  reinit_pf = true;
1107  } else if (param_name == "recovery_alpha_slow") {
1108  alpha_slow_ = parameter.as_double();
1109  reinit_pf = true;
1110  } else if (param_name == "save_pose_rate") {
1111  double save_pose_rate = parameter.as_double();
1112  save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
1113  } else if (param_name == "sigma_hit") {
1114  sigma_hit_ = parameter.as_double();
1115  reinit_laser = true;
1116  } else if (param_name == "transform_tolerance") {
1117  double tmp_tol = parameter.as_double();
1118  transform_tolerance_ = tf2::durationFromSec(tmp_tol);
1119  reinit_laser = true;
1120  } else if (param_name == "update_min_a") {
1121  a_thresh_ = parameter.as_double();
1122  } else if (param_name == "update_min_d") {
1123  d_thresh_ = parameter.as_double();
1124  } else if (param_name == "z_hit") {
1125  z_hit_ = parameter.as_double();
1126  reinit_laser = true;
1127  } else if (param_name == "z_max") {
1128  z_max_ = parameter.as_double();
1129  reinit_laser = true;
1130  } else if (param_name == "z_rand") {
1131  z_rand_ = parameter.as_double();
1132  reinit_laser = true;
1133  } else if (param_name == "z_short") {
1134  z_short_ = parameter.as_double();
1135  reinit_laser = true;
1136  }
1137  } else if (param_type == ParameterType::PARAMETER_STRING) {
1138  if (param_name == "base_frame_id") {
1139  base_frame_id_ = parameter.as_string();
1140  } else if (param_name == "global_frame_id") {
1141  global_frame_id_ = parameter.as_string();
1142  } else if (param_name == "map_topic") {
1143  map_topic_ = parameter.as_string();
1144  reinit_map = true;
1145  } else if (param_name == "laser_model_type") {
1146  sensor_model_type_ = parameter.as_string();
1147  reinit_laser = true;
1148  } else if (param_name == "odom_frame_id") {
1149  odom_frame_id_ = parameter.as_string();
1150  reinit_laser = true;
1151  } else if (param_name == "scan_topic") {
1152  scan_topic_ = parameter.as_string();
1153  reinit_laser = true;
1154  } else if (param_name == "robot_model_type") {
1155  robot_model_type_ = parameter.as_string();
1156  reinit_odom = true;
1157  }
1158  } else if (param_type == ParameterType::PARAMETER_BOOL) {
1159  if (param_name == "do_beamskip") {
1160  do_beamskip_ = parameter.as_bool();
1161  reinit_laser = true;
1162  } else if (param_name == "tf_broadcast") {
1163  tf_broadcast_ = parameter.as_bool();
1164  } else if (param_name == "set_initial_pose") {
1165  set_initial_pose_ = parameter.as_bool();
1166  } else if (param_name == "first_map_only") {
1167  first_map_only_ = parameter.as_bool();
1168  }
1169  } else if (param_type == ParameterType::PARAMETER_INTEGER) {
1170  if (param_name == "max_beams") {
1171  max_beams_ = parameter.as_int();
1172  reinit_laser = true;
1173  } else if (param_name == "max_particles") {
1174  max_particles_ = parameter.as_int();
1175  reinit_pf = true;
1176  } else if (param_name == "min_particles") {
1177  min_particles_ = parameter.as_int();
1178  reinit_pf = true;
1179  } else if (param_name == "resample_interval") {
1180  resample_interval_ = parameter.as_int();
1181  }
1182  }
1183  }
1184 
1185  // Re-initialize the particle filter
1186  if (reinit_pf) {
1187  if (pf_ != NULL) {
1188  pf_free(pf_);
1189  pf_ = NULL;
1190  }
1191  initParticleFilter();
1192  }
1193 
1194  // Re-initialize the odometry
1195  if (reinit_odom) {
1196  motion_model_.reset();
1197  initOdometry();
1198  }
1199 
1200  // Re-initialize the lasers and it's filters
1201  if (reinit_laser) {
1202  lasers_.clear();
1203  lasers_update_.clear();
1204  frame_to_laser_.clear();
1205  laser_scan_connection_.disconnect();
1206  laser_scan_filter_.reset();
1207  laser_scan_sub_.reset();
1208 
1209  initMessageFilters();
1210  }
1211 
1212  // Re-initialize the map
1213  if (reinit_map) {
1214  map_sub_.reset();
1215  map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1216  map_topic_,
1217  std::bind(&AmclNode::mapReceived, this, std::placeholders::_1),
1219  }
1220 }
1221 
1222 void
1223 AmclNode::mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
1224 {
1225  RCLCPP_DEBUG(get_logger(), "AmclNode: A new map was received.");
1226  if (!nav2::validateMsg(*msg)) {
1227  RCLCPP_ERROR(get_logger(), "Received map message is malformed. Rejecting.");
1228  return;
1229  }
1230  if (first_map_only_ && first_map_received_) {
1231  return;
1232  }
1233  handleMapMessage(*msg);
1234  first_map_received_ = true;
1235 }
1236 
1237 void
1238 AmclNode::handleMapMessage(const nav_msgs::msg::OccupancyGrid & msg)
1239 {
1240  std::lock_guard<std::recursive_mutex> cfl(mutex_);
1241 
1242  RCLCPP_INFO(
1243  get_logger(), "Received a %d X %d map @ %.3f m/pix",
1244  msg.info.width,
1245  msg.info.height,
1246  msg.info.resolution);
1247  if (msg.header.frame_id != global_frame_id_) {
1248  RCLCPP_WARN(
1249  get_logger(), "Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could"
1250  " cause issues with reading published topics",
1251  msg.header.frame_id.c_str(),
1252  global_frame_id_.c_str());
1253  }
1254  freeMapDependentMemory();
1255  map_ = convertMap(msg);
1256 
1257 #if NEW_UNIFORM_SAMPLING
1258  createFreeSpaceVector();
1259 #endif
1260 }
1261 
1262 void
1263 AmclNode::createFreeSpaceVector()
1264 {
1265  int delta = freespace_downsampling_ ? 2 : 1;
1266  // Index of free space
1267  free_space_indices.resize(0);
1268  for (int i = 0; i < map_->size_x; i += delta) {
1269  for (int j = 0; j < map_->size_y; j += delta) {
1270  if (map_->cells[MAP_INDEX(map_, i, j)].occ_state == -1) {
1271  AmclNode::Point2D point = {i, j};
1272  free_space_indices.push_back(point);
1273  }
1274  }
1275  }
1276 }
1277 
1278 void
1279 AmclNode::freeMapDependentMemory()
1280 {
1281  if (map_ != NULL) {
1282  map_free(map_);
1283  map_ = NULL;
1284  }
1285 
1286  // Clear queued laser objects because they hold pointers to the existing
1287  // map, #5202.
1288  lasers_.clear();
1289  lasers_update_.clear();
1290  frame_to_laser_.clear();
1291 }
1292 
1293 // Convert an OccupancyGrid map message into the internal representation. This function
1294 // allocates a map_t and returns it.
1295 map_t *
1296 AmclNode::convertMap(const nav_msgs::msg::OccupancyGrid & map_msg)
1297 {
1298  map_t * map = map_alloc();
1299 
1300  map->size_x = map_msg.info.width;
1301  map->size_y = map_msg.info.height;
1302  map->scale = map_msg.info.resolution;
1303  map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
1304  map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
1305 
1306  map->cells =
1307  reinterpret_cast<map_cell_t *>(malloc(sizeof(map_cell_t) * map->size_x * map->size_y));
1308 
1309  // Convert to player format
1310  for (int i = 0; i < map->size_x * map->size_y; i++) {
1311  if (map_msg.data[i] == 0) {
1312  map->cells[i].occ_state = -1;
1313  } else if (map_msg.data[i] == 100) {
1314  map->cells[i].occ_state = +1;
1315  } else {
1316  map->cells[i].occ_state = 0;
1317  }
1318  }
1319 
1320  return map;
1321 }
1322 
1323 void
1324 AmclNode::initTransforms()
1325 {
1326  RCLCPP_INFO(get_logger(), "initTransforms");
1327 
1328  // Initialize transform listener and broadcaster
1329  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
1330  auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
1331  get_node_base_interface(),
1332  get_node_timers_interface(),
1333  callback_group_);
1334  tf_buffer_->setCreateTimerInterface(timer_interface);
1335  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
1336  tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
1337 
1338  sent_first_transform_ = false;
1339  latest_tf_valid_ = false;
1340  latest_tf_ = tf2::Transform::getIdentity();
1341 }
1342 
1343 void
1344 AmclNode::initMessageFilters()
1345 {
1346  auto sub_opt = rclcpp::SubscriptionOptions();
1347  sub_opt.callback_group = callback_group_;
1348 
1349  #if RCLCPP_VERSION_GTE(29, 6, 0)
1350  laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
1351  shared_from_this(), scan_topic_, nav2::qos::SensorDataQoS(), sub_opt);
1352  #else
1353  laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
1354  rclcpp_lifecycle::LifecycleNode>>(
1355  std::static_pointer_cast<rclcpp_lifecycle::LifecycleNode>(shared_from_this()),
1356  scan_topic_, nav2::qos::SensorDataQoS().get_rmw_qos_profile(), sub_opt);
1357  #endif
1358 
1359  laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
1360  *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
1361  get_node_logging_interface(),
1362  get_node_clock_interface(),
1363  transform_tolerance_);
1364 
1365 
1366  laser_scan_connection_ = laser_scan_filter_->registerCallback(
1367  std::bind(&AmclNode::laserReceived, this, std::placeholders::_1));
1368 }
1369 
1370 void
1371 AmclNode::initPubSub()
1372 {
1373  RCLCPP_INFO(get_logger(), "initPubSub");
1374 
1375  particle_cloud_pub_ = create_publisher<nav2_msgs::msg::ParticleCloud>(
1376  "particle_cloud",
1378 
1379  pose_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
1380  "amcl_pose",
1382 
1383  initial_pose_sub_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
1384  "initialpose",
1385  std::bind(&AmclNode::initialPoseReceived, this, std::placeholders::_1));
1386 
1387  map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1388  map_topic_,
1389  std::bind(&AmclNode::mapReceived, this, std::placeholders::_1),
1391 
1392  RCLCPP_INFO(get_logger(), "Subscribed to map topic.");
1393 }
1394 
1395 void
1396 AmclNode::initServices()
1397 {
1398  global_loc_srv_ = create_service<std_srvs::srv::Empty>(
1399  "reinitialize_global_localization",
1400  std::bind(&AmclNode::globalLocalizationCallback, this, std::placeholders::_1,
1401  std::placeholders::_2, std::placeholders::_3));
1402 
1403  initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
1404  "set_initial_pose",
1405  std::bind(&AmclNode::initialPoseReceivedSrv, this, std::placeholders::_1, std::placeholders::_2,
1406  std::placeholders::_3));
1407 
1408  nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
1409  "request_nomotion_update",
1410  std::bind(&AmclNode::nomotionUpdateCallback, this, std::placeholders::_1, std::placeholders::_2,
1411  std::placeholders::_3));
1412 }
1413 
1414 void
1415 AmclNode::initOdometry()
1416 {
1417  // TODO(mjeronimo): We should handle persistence of the last known pose of the robot. We could
1418  // then read that pose here and initialize using that.
1419 
1420  // When pausing and resuming, remember the last robot pose so we don't start at 0:0 again
1421  init_pose_[0] = last_published_pose_.pose.pose.position.x;
1422  init_pose_[1] = last_published_pose_.pose.pose.position.y;
1423  init_pose_[2] = tf2::getYaw(last_published_pose_.pose.pose.orientation);
1424 
1425  if (!initial_pose_is_known_) {
1426  init_cov_[0] = 0.5 * 0.5;
1427  init_cov_[1] = 0.5 * 0.5;
1428  init_cov_[2] = (M_PI / 12.0) * (M_PI / 12.0);
1429  } else {
1430  init_cov_[0] = last_published_pose_.pose.covariance[0];
1431  init_cov_[1] = last_published_pose_.pose.covariance[7];
1432  init_cov_[2] = last_published_pose_.pose.covariance[35];
1433  }
1434 
1435  motion_model_ = plugin_loader_.createSharedInstance(robot_model_type_);
1436  motion_model_->initialize(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
1437 
1438  latest_odom_pose_ = geometry_msgs::msg::PoseStamped();
1439 }
1440 
1441 void
1442 AmclNode::initParticleFilter()
1443 {
1444  // Create the particle filter
1445  pf_ = pf_alloc(
1446  min_particles_, max_particles_, alpha_slow_, alpha_fast_,
1447  (pf_init_model_fn_t)AmclNode::uniformPoseGenerator);
1448  pf_->pop_err = pf_err_;
1449  pf_->pop_z = pf_z_;
1450 
1451  // Initialize the filter
1452  pf_vector_t pf_init_pose_mean = pf_vector_zero();
1453  pf_init_pose_mean.v[0] = init_pose_[0];
1454  pf_init_pose_mean.v[1] = init_pose_[1];
1455  pf_init_pose_mean.v[2] = init_pose_[2];
1456 
1457  pf_matrix_t pf_init_pose_cov = pf_matrix_zero();
1458  pf_init_pose_cov.m[0][0] = init_cov_[0];
1459  pf_init_pose_cov.m[1][1] = init_cov_[1];
1460  pf_init_pose_cov.m[2][2] = init_cov_[2];
1461 
1462  pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
1463 
1464  pf_init_ = false;
1465  resample_count_ = 0;
1466  memset(&pf_odom_pose_, 0, sizeof(pf_odom_pose_));
1467 }
1468 
1469 void
1470 AmclNode::initLaserScan()
1471 {
1472  scan_error_count_ = 0;
1473  last_laser_received_ts_ = rclcpp::Time(0);
1474 }
1475 
1476 } // namespace nav2_amcl
1477 
1478 #include "rclcpp_components/register_node_macro.hpp"
1479 
1480 // Register the component with class_loader.
1481 // This acts as a sort of entry point, allowing the component to be discoverable when its library
1482 // is being loaded into a running process.
1483 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_amcl::AmclNode)
A QoS profile for latched, reliable topics with a history of 1 messages.
A QoS profile for latched, reliable topics with a history of 10 messages.
A QoS profile for best-effort sensor data with a history of 10 messages.
Definition: map.hpp:62