Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
amcl_node.hpp
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 #ifndef NAV2_AMCL__AMCL_NODE_HPP_
22 #define NAV2_AMCL__AMCL_NODE_HPP_
23 
24 #include <atomic>
25 #include <map>
26 #include <memory>
27 #include <string>
28 #include <utility>
29 #include <vector>
30 
31 #include "message_filters/subscriber.hpp"
32 #include "rclcpp/version.h"
33 
34 #include "geometry_msgs/msg/pose_stamped.hpp"
35 #include "nav2_ros_common/lifecycle_node.hpp"
36 #include "nav2_amcl/motion_model/motion_model.hpp"
37 #include "nav2_amcl/sensors/laser/laser.hpp"
38 #include "nav2_msgs/msg/particle.hpp"
39 #include "nav2_msgs/msg/particle_cloud.hpp"
40 #include "nav2_msgs/srv/set_initial_pose.hpp"
41 #include "nav_msgs/srv/set_map.hpp"
42 #include "pluginlib/class_loader.hpp"
43 #include "rclcpp/node_options.hpp"
44 #include "sensor_msgs/msg/laser_scan.hpp"
45 #include "nav2_ros_common/service_server.hpp"
46 #include "std_srvs/srv/empty.hpp"
47 #include "tf2_ros/message_filter.hpp"
48 #include "tf2_ros/transform_broadcaster.hpp"
49 #include "tf2_ros/transform_listener.hpp"
50 
51 #define NEW_UNIFORM_SAMPLING 1
52 
53 namespace nav2_amcl
54 {
55 /*
56  * @class AmclNode
57  * @brief ROS wrapper for AMCL
58  */
60 {
61 public:
62  /*
63  * @brief AMCL constructor
64  * @param options Additional options to control creation of the node.
65  */
66  explicit AmclNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
67  /*
68  * @brief AMCL destructor
69  */
70  ~AmclNode();
71 
72 protected:
73  /*
74  * @brief Lifecycle configure
75  */
76  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
77  /*
78  * @brief Lifecycle activate
79  */
80  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
81  /*
82  * @brief Lifecycle deactivate
83  */
84  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
85  /*
86  * @brief Lifecycle cleanup
87  */
88  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
89  /*
90  * @brief Lifecycle shutdown
91  */
92  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
93 
102  rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(
103  std::vector<rclcpp::Parameter> parameters);
104 
111  void updateParametersCallback(std::vector<rclcpp::Parameter> parameters);
112 
113  // Dynamic parameters handler
114  rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr post_set_params_handler_;
115  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_params_handler_;
116 
117  // Since the sensor data from gazebo or the robot is not lifecycle enabled, we won't
118  // respond until we're in the active state
119  std::atomic<bool> active_{false};
120 
121  // Dedicated callback group and executor for services and subscriptions in AmclNode,
122  // in order to isolate TF timer used in message filter.
123  rclcpp::CallbackGroup::SharedPtr callback_group_;
124  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
125  std::unique_ptr<nav2::NodeThread> executor_thread_;
126 
127  // Pose hypothesis
128  typedef struct
129  {
130  double weight; // Total weight (weights sum to 1)
131  pf_vector_t pf_pose_mean; // Mean of pose estimate
132  pf_matrix_t pf_pose_cov; // Covariance of pose estimate
133  } amcl_hyp_t;
134 
135  // Map-related
136  /*
137  * @brief Get new map from ROS topic to localize in
138  * @param msg Map message
139  */
140  void mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
141  /*
142  * @brief Handle a new map message
143  * @param msg Map message
144  */
145  void handleMapMessage(const nav_msgs::msg::OccupancyGrid & msg);
146  /*
147  * @brief Creates lookup table of free cells in map
148  */
149  void createFreeSpaceVector();
150  /*
151  * @brief Frees allocated map related memory
152  */
153  void freeMapDependentMemory();
154  map_t * map_{nullptr};
155  /*
156  * @brief Convert an occupancy grid map to an AMCL map
157  * @param map_msg Map message
158  * @return pointer to map for AMCL to use
159  */
160  map_t * convertMap(const nav_msgs::msg::OccupancyGrid & map_msg);
161  bool first_map_only_{true};
162  std::atomic<bool> first_map_received_{false};
163  amcl_hyp_t * initial_pose_hyp_;
164  std::recursive_mutex mutex_;
165  nav2::Subscription<nav_msgs::msg::OccupancyGrid>::ConstSharedPtr map_sub_;
166 #if NEW_UNIFORM_SAMPLING
167  struct Point2D { int32_t x; int32_t y; };
168  static std::vector<Point2D> free_space_indices;
169 #endif
170 
171  // Transforms
172  /*
173  * @brief Initialize required ROS transformations
174  */
175  void initTransforms();
176  std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
177  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
178  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
179  bool sent_first_transform_{false};
180  bool latest_tf_valid_{false};
181  tf2::Transform latest_tf_;
182 
183  // Message filters
184  /*
185  * @brief Initialize incoming data message subscribers and filters
186  */
187  void initMessageFilters();
188 
189  // To Support Kilted and Older from Message Filters API change
190  #if RCLCPP_VERSION_GTE(29, 6, 0)
191  std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
192  #else
193  std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
194  rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
195  #endif
196 
197  std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
198  message_filters::Connection laser_scan_connection_;
199 
200  // Publishers and subscribers
201  /*
202  * @brief Initialize pub subs of AMCL
203  */
204  void initPubSub();
205  nav2::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr
206  initial_pose_sub_;
207  nav2::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
208  pose_pub_;
209  nav2::Publisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
210  particle_cloud_pub_;
211  /*
212  * @brief Handle with an initial pose estimate is received
213  */
214  void initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
215  /*
216  * @brief Handle when a laser scan is received
217  */
218  void laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan);
219 
220  // Services and service callbacks
221  /*
222  * @brief Initialize state services
223  */
224  void initServices();
225  nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr global_loc_srv_;
226  /*
227  * @brief Service callback for a global relocalization request
228  */
229  void globalLocalizationCallback(
230  const std::shared_ptr<rmw_request_id_t> request_header,
231  const std::shared_ptr<std_srvs::srv::Empty::Request> request,
232  std::shared_ptr<std_srvs::srv::Empty::Response> response);
233 
234  // service server for providing an initial pose guess
235  nav2::ServiceServer<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
236  /*
237  * @brief Service callback for an initial pose guess request
238  */
239  void initialPoseReceivedSrv(
240  const std::shared_ptr<rmw_request_id_t> request_header,
241  const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> request,
242  std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response> response);
243 
244  // Let amcl update samples without requiring motion
245  nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
246  /*
247  * @brief Request an AMCL update even though the robot hasn't moved
248  */
249  void nomotionUpdateCallback(
250  const std::shared_ptr<rmw_request_id_t> request_header,
251  const std::shared_ptr<std_srvs::srv::Empty::Request> request,
252  std::shared_ptr<std_srvs::srv::Empty::Response> response);
253 
254  // Nomotion update control. Used to temporarily let amcl update samples even when no motion occurs
255  std::atomic<bool> force_update_{false};
256 
257  // Odometry
258  /*
259  * @brief Initialize odometry
260  */
261  void initOdometry();
262  std::shared_ptr<nav2_amcl::MotionModel> motion_model_;
263  geometry_msgs::msg::PoseStamped latest_odom_pose_;
264  geometry_msgs::msg::PoseWithCovarianceStamped last_published_pose_;
265  double init_pose_[3]; // Initial robot pose
266  double init_cov_[3];
267  pluginlib::ClassLoader<nav2_amcl::MotionModel> plugin_loader_{"nav2_amcl",
268  "nav2_amcl::MotionModel"};
269  /*
270  * @brief Get robot pose in odom frame using TF
271  */
272  bool getOdomPose(
273  // Helper to get odometric pose from transform system
274  geometry_msgs::msg::PoseStamped & pose,
275  double & x, double & y, double & yaw,
276  const rclcpp::Time & sensor_timestamp, const std::string & frame_id);
277  std::atomic<bool> first_pose_sent_;
278 
279  // Particle filter
280  /*
281  * @brief Initialize particle filter
282  */
283  void initParticleFilter();
284  /*
285  * @brief Pose-generating function used to uniformly distribute particles over the map
286  */
287  static pf_vector_t uniformPoseGenerator(void * arg);
288  pf_t * pf_{nullptr};
289  bool pf_init_;
290  pf_vector_t pf_odom_pose_;
291  int resample_count_{0};
292 
293  // Laser scan related
294  /*
295  * @brief Initialize laser scan
296  */
297  void initLaserScan();
298  /*
299  * @brief Create a laser object
300  */
301  nav2_amcl::Laser * createLaserObject();
302  int scan_error_count_{0};
303  std::vector<nav2_amcl::Laser *> lasers_;
304  std::vector<bool> lasers_update_;
305  std::map<std::string, int> frame_to_laser_;
306  rclcpp::Time last_laser_received_ts_;
307 
308  /*
309  * @brief Check if sufficient time has elapsed to get an update
310  */
311  bool checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time);
312  rclcpp::Time last_time_printed_msg_;
313  /*
314  * @brief Add a new laser scanner if a new one is received in the laser scallbacks
315  */
316  bool addNewScanner(
317  int & laser_index,
318  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
319  const std::string & laser_scan_frame_id,
320  geometry_msgs::msg::PoseStamped & laser_pose);
321  /*
322  * @brief Whether the pf needs to be updated
323  */
324  bool shouldUpdateFilter(const pf_vector_t pose, pf_vector_t & delta);
325  /*
326  * @brief Update the PF
327  */
328  bool updateFilter(
329  const int & laser_index,
330  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
331  const pf_vector_t & pose);
332  /*
333  * @brief Publish particle cloud
334  */
335  void publishParticleCloud(const pf_sample_set_t * set);
336  /*
337  * @brief Get the current state estimat hypothesis from the particle cloud
338  */
339  bool getMaxWeightHyp(
340  std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
341  int & max_weight_hyp);
342  /*
343  * @brief Publish robot pose in map frame from AMCL
344  */
345  void publishAmclPose(
346  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
347  const std::vector<amcl_hyp_t> & hyps, const int & max_weight_hyp);
348  /*
349  * @brief Determine TF transformation from map to odom
350  */
351  void calculateMaptoOdomTransform(
352  const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
353  const std::vector<amcl_hyp_t> & hyps,
354  const int & max_weight_hyp);
355  /*
356  * @brief Publish TF transformation from map to odom
357  */
358  void sendMapToOdomTransform(const tf2::TimePoint & transform_expiration);
359  /*
360  * @brief Handle a new pose estimate callback
361  */
362  void handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg);
363  bool init_pose_received_on_inactive{false};
364  bool initial_pose_is_known_{false};
365  bool set_initial_pose_{false};
366  bool always_reset_initial_pose_;
367  double initial_pose_x_;
368  double initial_pose_y_;
369  double initial_pose_z_;
370  double initial_pose_yaw_;
371 
372  /*
373  * @brief Get ROS parameters for node
374  */
375  void initParameters();
376  double alpha1_;
377  double alpha2_;
378  double alpha3_;
379  double alpha4_;
380  double alpha5_;
381  std::string base_frame_id_;
382  double beam_skip_distance_;
383  double beam_skip_error_threshold_;
384  double beam_skip_threshold_;
385  bool do_beamskip_;
386  std::string global_frame_id_;
387  double lambda_short_;
388  double laser_likelihood_max_dist_;
389  double laser_max_range_;
390  double laser_min_range_;
391  std::string sensor_model_type_;
392  int max_beams_;
393  int max_particles_;
394  int min_particles_;
395  std::string odom_frame_id_;
396  double pf_err_;
397  double pf_z_;
398  double alpha_fast_;
399  double alpha_slow_;
400  int resample_interval_;
401  std::string robot_model_type_;
402  tf2::Duration save_pose_period_;
403  double sigma_hit_;
404  bool tf_broadcast_;
405  tf2::Duration transform_tolerance_;
406  double a_thresh_;
407  double d_thresh_;
408  double z_hit_;
409  double z_max_;
410  double z_short_;
411  double z_rand_;
412  std::string scan_topic_{"scan"};
413  std::string map_topic_{"map"};
414  bool freespace_downsampling_ = false;
415 };
416 
417 } // namespace nav2_amcl
418 
419 #endif // NAV2_AMCL__AMCL_NODE_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
void updateParametersCallback(std::vector< rclcpp::Parameter > parameters)
Apply parameter updates after validation This callback is executed when parameters have been successf...
Definition: amcl_node.cpp:1045
rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(std::vector< rclcpp::Parameter > parameters)
Validate incoming parameter updates before applying them. This callback is triggered when one or more...
Definition: amcl_node.cpp:995
Definition: pf.hpp:112
Definition: map.hpp:62