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