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