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