21 #ifndef NAV2_AMCL__AMCL_NODE_HPP_
22 #define NAV2_AMCL__AMCL_NODE_HPP_
31 #include "message_filters/subscriber.hpp"
32 #include "rclcpp/version.h"
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"
51 #define NEW_UNIFORM_SAMPLING 1
66 explicit AmclNode(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
76 nav2::CallbackReturn on_configure(
const rclcpp_lifecycle::State & state)
override;
80 nav2::CallbackReturn on_activate(
const rclcpp_lifecycle::State & state)
override;
84 nav2::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & state)
override;
88 nav2::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & state)
override;
92 nav2::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & state)
override;
103 std::vector<rclcpp::Parameter> parameters);
114 rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr post_set_params_handler_;
115 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_params_handler_;
119 std::atomic<bool> active_{
false};
123 rclcpp::CallbackGroup::SharedPtr callback_group_;
124 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
125 std::unique_ptr<nav2::NodeThread> executor_thread_;
140 void mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
145 void handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg);
149 void createFreeSpaceVector();
153 void freeMapDependentMemory();
154 map_t * map_{
nullptr};
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
168 static std::vector<Point2D> free_space_indices;
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_;
187 void initMessageFilters();
190 #if RCLCPP_VERSION_GTE(29, 6, 0)
191 std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
193 std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
194 rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
197 std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
198 message_filters::Connection laser_scan_connection_;
205 nav2::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr
207 nav2::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
209 nav2::Publisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
214 void initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
218 void laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan);
225 nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr global_loc_srv_;
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);
235 nav2::ServiceServer<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
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);
245 nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
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);
255 std::atomic<bool> force_update_{
false};
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];
267 pluginlib::ClassLoader<nav2_amcl::MotionModel> plugin_loader_{
"nav2_amcl",
268 "nav2_amcl::MotionModel"};
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_;
283 void initParticleFilter();
287 static pf_vector_t uniformPoseGenerator(
void * arg);
291 int resample_count_{0};
297 void initLaserScan();
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_;
311 bool checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time);
312 rclcpp::Time last_time_printed_msg_;
318 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
319 const std::string & laser_scan_frame_id,
320 geometry_msgs::msg::PoseStamped & laser_pose);
329 const int & laser_index,
330 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
339 bool getMaxWeightHyp(
340 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
341 int & max_weight_hyp);
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);
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);
358 void sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration);
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_;
375 void initParameters();
381 std::string base_frame_id_;
382 double beam_skip_distance_;
383 double beam_skip_error_threshold_;
384 double beam_skip_threshold_;
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_;
395 std::string odom_frame_id_;
400 int resample_interval_;
401 std::string robot_model_type_;
402 tf2::Duration save_pose_period_;
405 tf2::Duration transform_tolerance_;
412 std::string scan_topic_{
"scan"};
413 std::string map_topic_{
"map"};
414 bool freespace_downsampling_ =
false;
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...
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...