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