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