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