21 #ifndef NAV2_AMCL__AMCL_NODE_HPP_
22 #define NAV2_AMCL__AMCL_NODE_HPP_
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"
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
52 #define NEW_UNIFORM_SAMPLING 1
67 explicit AmclNode(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
77 nav2_util::CallbackReturn on_configure(
const rclcpp_lifecycle::State & state)
override;
81 nav2_util::CallbackReturn on_activate(
const rclcpp_lifecycle::State & state)
override;
85 nav2_util::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & state)
override;
89 nav2_util::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & state)
override;
93 nav2_util::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & state)
override;
99 rcl_interfaces::msg::SetParametersResult
103 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
107 std::atomic<bool> active_{
false};
111 rclcpp::CallbackGroup::SharedPtr callback_group_;
112 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
113 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
128 void mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
133 void handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg);
137 void createFreeSpaceVector();
141 void freeMapDependentMemory();
142 map_t * map_{
nullptr};
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;
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();
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_;
185 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr
187 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
189 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
194 void initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
198 void laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan);
205 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr global_loc_srv_;
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);
215 rclcpp::Service<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
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);
225 rclcpp::Service<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
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);
235 std::atomic<bool> force_update_{
false};
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];
247 pluginlib::ClassLoader<nav2_amcl::MotionModel> plugin_loader_{
"nav2_amcl",
248 "nav2_amcl::MotionModel"};
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_;
263 void initParticleFilter();
267 static pf_vector_t uniformPoseGenerator(
void * arg);
271 int resample_count_{0};
277 void initLaserScan();
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_;
291 bool checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time);
292 rclcpp::Time last_time_printed_msg_;
298 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
299 const std::string & laser_scan_frame_id,
300 geometry_msgs::msg::PoseStamped & laser_pose);
309 const int & laser_index,
310 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
319 bool getMaxWeightHyp(
320 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
321 int & max_weight_hyp);
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);
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);
338 void sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration);
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_;
355 void initParameters();
361 std::string base_frame_id_;
362 double beam_skip_distance_;
363 double beam_skip_error_threshold_;
364 double beam_skip_threshold_;
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_;
375 std::string odom_frame_id_;
380 int resample_interval_;
381 std::string robot_model_type_;
382 tf2::Duration save_pose_period_;
385 tf2::Duration transform_tolerance_;
392 std::string scan_topic_{
"scan"};
393 std::string map_topic_{
"map"};
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.