21 #ifndef NAV2_AMCL__AMCL_NODE_HPP_
22 #define NAV2_AMCL__AMCL_NODE_HPP_
31 #include "message_filters/subscriber.hpp"
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"
50 #define NEW_UNIFORM_SAMPLING 1
65 explicit AmclNode(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
75 nav2_util::CallbackReturn on_configure(
const rclcpp_lifecycle::State & state)
override;
79 nav2_util::CallbackReturn on_activate(
const rclcpp_lifecycle::State & state)
override;
83 nav2_util::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & state)
override;
87 nav2_util::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State & state)
override;
91 nav2_util::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State & state)
override;
97 rcl_interfaces::msg::SetParametersResult
101 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
105 std::atomic<bool> active_{
false};
109 rclcpp::CallbackGroup::SharedPtr callback_group_;
110 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
111 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
126 void mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
131 void handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg);
135 void createFreeSpaceVector();
139 void freeMapDependentMemory();
140 map_t * map_{
nullptr};
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
154 static std::vector<Point2D> free_space_indices;
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_;
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_;
184 rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr
186 rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
188 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::ParticleCloud>::SharedPtr
193 void initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
197 void laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan);
205 std::shared_ptr<nav2_util::LifecycleNode>>::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);
216 std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr initial_guess_srv_;
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);
227 std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr nomotion_update_srv_;
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);
237 std::atomic<bool> force_update_{
false};
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];
249 pluginlib::ClassLoader<nav2_amcl::MotionModel> plugin_loader_{
"nav2_amcl",
250 "nav2_amcl::MotionModel"};
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_;
265 void initParticleFilter();
269 static pf_vector_t uniformPoseGenerator(
void * arg);
273 int resample_count_{0};
279 void initLaserScan();
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_;
293 bool checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time);
294 rclcpp::Time last_time_printed_msg_;
300 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
301 const std::string & laser_scan_frame_id,
302 geometry_msgs::msg::PoseStamped & laser_pose);
311 const int & laser_index,
312 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
321 bool getMaxWeightHyp(
322 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
323 int & max_weight_hyp);
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);
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);
340 void sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration);
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_;
357 void initParameters();
363 std::string base_frame_id_;
364 double beam_skip_distance_;
365 double beam_skip_error_threshold_;
366 double beam_skip_threshold_;
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_;
377 std::string odom_frame_id_;
382 int resample_interval_;
383 std::string robot_model_type_;
384 tf2::Duration save_pose_period_;
387 tf2::Duration transform_tolerance_;
394 std::string scan_topic_{
"scan"};
395 std::string map_topic_{
"map"};
396 bool freespace_downsampling_ =
false;
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.
A simple wrapper on ROS2 services server.