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;
98 rcl_interfaces::msg::SetParametersResult
102 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
106 std::atomic<bool> active_{
false};
110 rclcpp::CallbackGroup::SharedPtr callback_group_;
111 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
112 std::unique_ptr<nav2::NodeThread> executor_thread_;
127 void mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
132 void handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg);
136 void createFreeSpaceVector();
140 void freeMapDependentMemory();
141 map_t * map_{
nullptr};
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
155 static std::vector<Point2D> free_space_indices;
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_;
174 void initMessageFilters();
177 #if RCLCPP_VERSION_GTE(29, 6, 0)
178 std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
180 std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
181 rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
184 std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
185 message_filters::Connection laser_scan_connection_;
192 nav2::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr
194 nav2::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
196 nav2::Publisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
201 void initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
205 void laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan);
212 nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr global_loc_srv_;
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);
222 nav2::ServiceServer<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
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);
232 nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
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);
242 std::atomic<bool> force_update_{
false};
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];
254 pluginlib::ClassLoader<nav2_amcl::MotionModel> plugin_loader_{
"nav2_amcl",
255 "nav2_amcl::MotionModel"};
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_;
270 void initParticleFilter();
274 static pf_vector_t uniformPoseGenerator(
void * arg);
278 int resample_count_{0};
284 void initLaserScan();
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_;
298 bool checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time);
299 rclcpp::Time last_time_printed_msg_;
305 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
306 const std::string & laser_scan_frame_id,
307 geometry_msgs::msg::PoseStamped & laser_pose);
316 const int & laser_index,
317 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
326 bool getMaxWeightHyp(
327 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
328 int & max_weight_hyp);
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);
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);
345 void sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration);
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_;
362 void initParameters();
368 std::string base_frame_id_;
369 double beam_skip_distance_;
370 double beam_skip_error_threshold_;
371 double beam_skip_threshold_;
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_;
382 std::string odom_frame_id_;
387 int resample_interval_;
388 std::string robot_model_type_;
389 tf2::Duration save_pose_period_;
392 tf2::Duration transform_tolerance_;
399 std::string scan_topic_{
"scan"};
400 std::string map_topic_{
"map"};
401 bool freespace_downsampling_ =
false;
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.