23 #include "nav2_amcl/amcl_node.hpp"
31 #include "message_filters/subscriber.h"
32 #include "nav2_amcl/angleutils.hpp"
33 #include "nav2_util/geometry_utils.hpp"
34 #include "nav2_amcl/pf/pf.hpp"
35 #include "nav2_util/string_utils.hpp"
36 #include "nav2_amcl/sensors/laser/laser.hpp"
37 #include "tf2/convert.h"
38 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
39 #include "tf2/LinearMath/Transform.h"
40 #include "tf2_ros/buffer.h"
41 #include "tf2_ros/message_filter.h"
42 #include "tf2_ros/transform_broadcaster.h"
43 #include "tf2_ros/transform_listener.h"
44 #include "tf2_ros/create_timer_ros.h"
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wpedantic"
48 #include "tf2/utils.h"
49 #pragma GCC diagnostic pop
51 #include "nav2_amcl/portable_utils.hpp"
52 #include "nav2_util/validate_messages.hpp"
54 using namespace std::placeholders;
55 using rcl_interfaces::msg::ParameterType;
56 using namespace std::chrono_literals;
60 using nav2_util::geometry_utils::orientationAroundZAxis;
62 AmclNode::AmclNode(
const rclcpp::NodeOptions & options)
63 : nav2_util::LifecycleNode(
"amcl",
"", options)
65 RCLCPP_INFO(get_logger(),
"Creating");
68 "alpha1", rclcpp::ParameterValue(0.2),
69 "This is the alpha1 parameter",
"These are additional constraints for alpha1");
72 "alpha2", rclcpp::ParameterValue(0.2),
73 "This is the alpha2 parameter",
"These are additional constraints for alpha2");
76 "alpha3", rclcpp::ParameterValue(0.2),
77 "This is the alpha3 parameter",
"These are additional constraints for alpha3");
80 "alpha4", rclcpp::ParameterValue(0.2),
81 "This is the alpha4 parameter",
"These are additional constraints for alpha4");
84 "alpha5", rclcpp::ParameterValue(0.2),
85 "This is the alpha5 parameter",
"These are additional constraints for alpha5");
88 "base_frame_id", rclcpp::ParameterValue(std::string(
"base_footprint")),
89 "Which frame to use for the robot base");
91 add_parameter(
"beam_skip_distance", rclcpp::ParameterValue(0.5));
92 add_parameter(
"beam_skip_error_threshold", rclcpp::ParameterValue(0.9));
93 add_parameter(
"beam_skip_threshold", rclcpp::ParameterValue(0.3));
94 add_parameter(
"do_beamskip", rclcpp::ParameterValue(
false));
97 "global_frame_id", rclcpp::ParameterValue(std::string(
"map")),
98 "The name of the coordinate frame published by the localization system");
101 "lambda_short", rclcpp::ParameterValue(0.1),
102 "Exponential decay parameter for z_short part of model");
105 "laser_likelihood_max_dist", rclcpp::ParameterValue(2.0),
106 "Maximum distance to do obstacle inflation on map, for use in likelihood_field model");
109 "laser_max_range", rclcpp::ParameterValue(100.0),
110 "Maximum scan range to be considered",
111 "-1.0 will cause the laser's reported maximum range to be used");
114 "laser_min_range", rclcpp::ParameterValue(-1.0),
115 "Minimum scan range to be considered",
116 "-1.0 will cause the laser's reported minimum range to be used");
119 "laser_model_type", rclcpp::ParameterValue(std::string(
"likelihood_field")),
120 "Which model to use, either beam, likelihood_field, or likelihood_field_prob",
121 "Same as likelihood_field but incorporates the beamskip feature, if enabled");
124 "set_initial_pose", rclcpp::ParameterValue(
false),
125 "Causes AMCL to set initial pose from the initial_pose* parameters instead of "
126 "waiting for the initial_pose message");
129 "initial_pose.x", rclcpp::ParameterValue(0.0),
130 "X coordinate of the initial robot pose in the map frame");
133 "initial_pose.y", rclcpp::ParameterValue(0.0),
134 "Y coordinate of the initial robot pose in the map frame");
137 "initial_pose.z", rclcpp::ParameterValue(0.0),
138 "Z coordinate of the initial robot pose in the map frame");
141 "initial_pose.yaw", rclcpp::ParameterValue(0.0),
142 "Yaw of the initial robot pose in the map frame");
145 "max_beams", rclcpp::ParameterValue(60),
146 "How many evenly-spaced beams in each scan to be used when updating the filter");
149 "max_particles", rclcpp::ParameterValue(2000),
150 "Maximum allowed number of particles");
153 "min_particles", rclcpp::ParameterValue(500),
154 "Minimum allowed number of particles");
157 "odom_frame_id", rclcpp::ParameterValue(std::string(
"odom")),
158 "Which frame to use for odometry");
160 add_parameter(
"pf_err", rclcpp::ParameterValue(0.05));
161 add_parameter(
"pf_z", rclcpp::ParameterValue(0.99));
164 "recovery_alpha_fast", rclcpp::ParameterValue(0.0),
165 "Exponential decay rate for the fast average weight filter, used in deciding when to recover "
166 "by adding random poses",
167 "A good value might be 0.1");
170 "recovery_alpha_slow", rclcpp::ParameterValue(0.0),
171 "Exponential decay rate for the slow average weight filter, used in deciding when to recover "
172 "by adding random poses",
173 "A good value might be 0.001");
176 "resample_interval", rclcpp::ParameterValue(1),
177 "Number of filter updates required before resampling");
179 add_parameter(
"robot_model_type", rclcpp::ParameterValue(
"nav2_amcl::DifferentialMotionModel"));
182 "save_pose_rate", rclcpp::ParameterValue(0.5),
183 "Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter "
184 "server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used "
185 "on subsequent runs to initialize the filter",
188 add_parameter(
"sigma_hit", rclcpp::ParameterValue(0.2));
191 "tf_broadcast", rclcpp::ParameterValue(
true),
192 "Set this to false to prevent amcl from publishing the transform between the global frame and "
193 "the odometry frame");
196 "transform_tolerance", rclcpp::ParameterValue(1.0),
197 "Time with which to post-date the transform that is published, to indicate that this transform "
198 "is valid into the future");
201 "update_min_a", rclcpp::ParameterValue(0.2),
202 "Rotational movement required before performing a filter update");
205 "update_min_d", rclcpp::ParameterValue(0.25),
206 "Translational movement required before performing a filter update");
208 add_parameter(
"z_hit", rclcpp::ParameterValue(0.5));
209 add_parameter(
"z_max", rclcpp::ParameterValue(0.05));
210 add_parameter(
"z_rand", rclcpp::ParameterValue(0.5));
211 add_parameter(
"z_short", rclcpp::ParameterValue(0.05));
214 "always_reset_initial_pose", rclcpp::ParameterValue(
false),
215 "Requires that AMCL is provided an initial pose either via topic or initial_pose* parameter "
216 "(with parameter set_initial_pose: true) when reset. Otherwise, by default AMCL will use the"
217 "last known pose to initialize");
220 "scan_topic", rclcpp::ParameterValue(
"scan"),
221 "Topic to subscribe to in order to receive the laser scan for localization");
224 "map_topic", rclcpp::ParameterValue(
"map"),
225 "Topic to subscribe to in order to receive the map to localize on");
228 "first_map_only", rclcpp::ParameterValue(
false),
229 "Set this to true, when you want to load a new map published from the map_server");
232 AmclNode::~AmclNode()
236 nav2_util::CallbackReturn
237 AmclNode::on_configure(
const rclcpp_lifecycle::State & )
239 RCLCPP_INFO(get_logger(),
"Configuring");
240 callback_group_ = create_callback_group(
241 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
244 initParticleFilter();
246 initMessageFilters();
250 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
251 executor_->add_callback_group(callback_group_, get_node_base_interface());
252 executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
253 return nav2_util::CallbackReturn::SUCCESS;
256 nav2_util::CallbackReturn
257 AmclNode::on_activate(
const rclcpp_lifecycle::State & )
259 RCLCPP_INFO(get_logger(),
"Activating");
262 pose_pub_->on_activate();
263 particle_cloud_pub_->on_activate();
265 first_pose_sent_ =
false;
271 if (set_initial_pose_) {
272 auto msg = std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>();
274 msg->header.stamp = now();
275 msg->header.frame_id = global_frame_id_;
276 msg->pose.pose.position.x = initial_pose_x_;
277 msg->pose.pose.position.y = initial_pose_y_;
278 msg->pose.pose.position.z = initial_pose_z_;
279 msg->pose.pose.orientation = orientationAroundZAxis(initial_pose_yaw_);
281 initialPoseReceived(msg);
282 }
else if (init_pose_received_on_inactive) {
283 handleInitialPose(last_published_pose_);
286 auto node = shared_from_this();
288 dyn_params_handler_ = node->add_on_set_parameters_callback(
290 &AmclNode::dynamicParametersCallback,
291 this, std::placeholders::_1));
296 return nav2_util::CallbackReturn::SUCCESS;
299 nav2_util::CallbackReturn
300 AmclNode::on_deactivate(
const rclcpp_lifecycle::State & )
302 RCLCPP_INFO(get_logger(),
"Deactivating");
307 pose_pub_->on_deactivate();
308 particle_cloud_pub_->on_deactivate();
311 dyn_params_handler_.reset();
316 return nav2_util::CallbackReturn::SUCCESS;
319 nav2_util::CallbackReturn
320 AmclNode::on_cleanup(
const rclcpp_lifecycle::State & )
322 RCLCPP_INFO(get_logger(),
"Cleaning up");
324 executor_thread_.reset();
328 global_loc_srv_.reset();
329 initial_guess_srv_.reset();
330 nomotion_update_srv_.reset();
331 executor_thread_.reset();
332 initial_pose_sub_.reset();
333 laser_scan_connection_.disconnect();
334 tf_listener_.reset();
335 laser_scan_filter_.reset();
336 laser_scan_sub_.reset();
344 first_map_received_ =
false;
345 free_space_indices.resize(0);
348 tf_broadcaster_.reset();
353 particle_cloud_pub_.reset();
356 motion_model_.reset();
364 lasers_update_.clear();
365 frame_to_laser_.clear();
366 force_update_ =
true;
368 if (set_initial_pose_) {
372 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.x)));
376 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.y)));
380 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.z)));
384 rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation))));
387 return nav2_util::CallbackReturn::SUCCESS;
390 nav2_util::CallbackReturn
391 AmclNode::on_shutdown(
const rclcpp_lifecycle::State & )
393 RCLCPP_INFO(get_logger(),
"Shutting down");
394 return nav2_util::CallbackReturn::SUCCESS;
398 AmclNode::checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time)
400 rclcpp::Duration elapsed_time = now() - last_time;
401 if (elapsed_time.nanoseconds() * 1e-9 > check_interval.count()) {
407 #if NEW_UNIFORM_SAMPLING
408 std::vector<std::pair<int, int>> AmclNode::free_space_indices;
412 AmclNode::getOdomPose(
413 geometry_msgs::msg::PoseStamped & odom_pose,
414 double & x,
double & y,
double & yaw,
415 const rclcpp::Time & sensor_timestamp,
const std::string & frame_id)
418 geometry_msgs::msg::PoseStamped ident;
419 ident.header.frame_id = nav2_util::strip_leading_slash(frame_id);
420 ident.header.stamp = sensor_timestamp;
421 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
424 tf_buffer_->transform(ident, odom_pose, odom_frame_id_);
425 }
catch (tf2::TransformException & e) {
427 if (scan_error_count_ % 20 == 0) {
429 get_logger(),
"(%d) consecutive laser scan transforms failed: (%s)", scan_error_count_,
435 scan_error_count_ = 0;
436 x = odom_pose.pose.position.x;
437 y = odom_pose.pose.position.y;
438 yaw = tf2::getYaw(odom_pose.pose.orientation);
444 AmclNode::uniformPoseGenerator(
void * arg)
448 #if NEW_UNIFORM_SAMPLING
449 unsigned int rand_index = drand48() * free_space_indices.size();
450 std::pair<int, int> free_point = free_space_indices[rand_index];
452 p.v[0] = MAP_WXGX(map, free_point.first);
453 p.v[1] = MAP_WYGY(map, free_point.second);
454 p.v[2] = drand48() * 2 * M_PI - M_PI;
456 double min_x, max_x, min_y, max_y;
458 min_x = (map->size_x * map->scale) / 2.0 - map->origin_x;
459 max_x = (map->size_x * map->scale) / 2.0 + map->origin_x;
460 min_y = (map->size_y * map->scale) / 2.0 - map->origin_y;
461 max_y = (map->size_y * map->scale) / 2.0 + map->origin_y;
465 RCLCPP_DEBUG(get_logger(),
"Generating new uniform sample");
467 p.v[0] = min_x + drand48() * (max_x - min_x);
468 p.v[1] = min_y + drand48() * (max_y - min_y);
469 p.v[2] = drand48() * 2 * M_PI - M_PI;
472 i = MAP_GXWX(map, p.v[0]);
473 j = MAP_GYWY(map, p.v[1]);
474 if (MAP_VALID(map, i, j) && (map->cells[MAP_INDEX(map, i, j)].occ_state == -1)) {
483 AmclNode::globalLocalizationCallback(
484 const std::shared_ptr<rmw_request_id_t>,
485 const std::shared_ptr<std_srvs::srv::Empty::Request>,
486 std::shared_ptr<std_srvs::srv::Empty::Response>)
488 std::lock_guard<std::recursive_mutex> cfl(mutex_);
490 RCLCPP_INFO(get_logger(),
"Initializing with uniform distribution");
493 pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
494 reinterpret_cast<void *
>(map_));
495 RCLCPP_INFO(get_logger(),
"Global initialisation done!");
496 initial_pose_is_known_ =
true;
501 AmclNode::initialPoseReceivedSrv(
502 const std::shared_ptr<rmw_request_id_t>,
503 const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
504 std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>)
506 initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
511 AmclNode::nomotionUpdateCallback(
512 const std::shared_ptr<rmw_request_id_t>,
513 const std::shared_ptr<std_srvs::srv::Empty::Request>,
514 std::shared_ptr<std_srvs::srv::Empty::Response>)
516 RCLCPP_INFO(get_logger(),
"Requesting no-motion update");
517 force_update_ =
true;
521 AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
523 std::lock_guard<std::recursive_mutex> cfl(mutex_);
525 RCLCPP_INFO(get_logger(),
"initialPoseReceived");
527 if (!nav2_util::validateMsg(*msg)) {
528 RCLCPP_ERROR(get_logger(),
"Received initialpose message is malformed. Rejecting.");
531 if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) {
534 "Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
535 nav2_util::strip_leading_slash(msg->header.frame_id).c_str(),
536 global_frame_id_.c_str());
540 last_published_pose_ = *msg;
543 init_pose_received_on_inactive =
true;
545 get_logger(),
"Received initial pose request, "
546 "but AMCL is not yet in the active state");
549 handleInitialPose(*msg);
553 AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
555 std::lock_guard<std::recursive_mutex> cfl(mutex_);
558 geometry_msgs::msg::TransformStamped tx_odom;
560 rclcpp::Time rclcpp_time = now();
561 tf2::TimePoint tf2_time(std::chrono::nanoseconds(rclcpp_time.nanoseconds()));
564 tx_odom = tf_buffer_->lookupTransform(
565 base_frame_id_, tf2_ros::fromMsg(msg.header.stamp),
566 base_frame_id_, tf2_time, odom_frame_id_);
567 }
catch (tf2::TransformException & e) {
572 if (sent_first_transform_) {
573 RCLCPP_WARN(get_logger(),
"Failed to transform initial pose in time (%s)", e.what());
575 tf2::impl::Converter<false, true>::convert(tf2::Transform::getIdentity(), tx_odom.transform);
578 tf2::Transform tx_odom_tf2;
579 tf2::impl::Converter<true, false>::convert(tx_odom.transform, tx_odom_tf2);
581 tf2::Transform pose_old;
582 tf2::impl::Converter<true, false>::convert(msg.pose.pose, pose_old);
584 tf2::Transform pose_new = pose_old * tx_odom_tf2;
589 get_logger(),
"Setting pose (%.6f): %.3f %.3f %.3f",
590 now().nanoseconds() * 1e-9,
591 pose_new.getOrigin().x(),
592 pose_new.getOrigin().y(),
593 tf2::getYaw(pose_new.getRotation()));
597 pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
598 pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
599 pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
603 for (
int i = 0; i < 2; i++) {
604 for (
int j = 0; j < 2; j++) {
605 pf_init_pose_cov.m[i][j] = msg.pose.covariance[6 * i + j];
609 pf_init_pose_cov.m[2][2] = msg.pose.covariance[6 * 5 + 5];
611 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
613 init_pose_received_on_inactive =
false;
614 initial_pose_is_known_ =
true;
618 AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
620 std::lock_guard<std::recursive_mutex> cfl(mutex_);
624 if (!active_) {
return;}
625 if (!first_map_received_) {
626 if (checkElapsedTime(2s, last_time_printed_msg_)) {
627 RCLCPP_WARN(get_logger(),
"Waiting for map....");
628 last_time_printed_msg_ = now();
633 std::string laser_scan_frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id);
634 last_laser_received_ts_ = now();
635 int laser_index = -1;
636 geometry_msgs::msg::PoseStamped laser_pose;
639 if (frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) {
640 if (!addNewScanner(laser_index, laser_scan, laser_scan_frame_id, laser_pose)) {
645 laser_index = frame_to_laser_[laser_scan->header.frame_id];
651 latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
652 laser_scan->header.stamp, base_frame_id_))
654 RCLCPP_ERROR(get_logger(),
"Couldn't determine robot's pose associated with laser scan");
659 bool force_publication =
false;
662 pf_odom_pose_ = pose;
665 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
666 lasers_update_[i] =
true;
669 force_publication =
true;
673 if (shouldUpdateFilter(pose, delta)) {
674 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
675 lasers_update_[i] =
true;
678 if (lasers_update_[laser_index]) {
679 motion_model_->odometryUpdate(pf_, pose, delta);
681 force_update_ =
false;
684 bool resampled =
false;
687 if (lasers_update_[laser_index]) {
688 updateFilter(laser_index, laser_scan, pose);
691 if (!(++resample_count_ % resample_interval_)) {
692 pf_update_resample(pf_,
reinterpret_cast<void *
>(map_));
697 RCLCPP_DEBUG(get_logger(),
"Num samples: %d\n", set->sample_count);
699 if (!force_update_) {
700 publishParticleCloud(set);
703 if (resampled || force_publication || !first_pose_sent_) {
704 amcl_hyp_t max_weight_hyps;
705 std::vector<amcl_hyp_t> hyps;
706 int max_weight_hyp = -1;
707 if (getMaxWeightHyp(hyps, max_weight_hyps, max_weight_hyp)) {
708 publishAmclPose(laser_scan, hyps, max_weight_hyp);
709 calculateMaptoOdomTransform(laser_scan, hyps, max_weight_hyp);
711 if (tf_broadcast_ ==
true) {
714 auto stamp = tf2_ros::fromMsg(laser_scan->header.stamp);
715 tf2::TimePoint transform_expiration = stamp + transform_tolerance_;
716 sendMapToOdomTransform(transform_expiration);
717 sent_first_transform_ =
true;
720 RCLCPP_ERROR(get_logger(),
"No pose!");
722 }
else if (latest_tf_valid_) {
723 if (tf_broadcast_ ==
true) {
726 tf2::TimePoint transform_expiration = tf2_ros::fromMsg(laser_scan->header.stamp) +
727 transform_tolerance_;
728 sendMapToOdomTransform(transform_expiration);
733 bool AmclNode::addNewScanner(
735 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
736 const std::string & laser_scan_frame_id,
737 geometry_msgs::msg::PoseStamped & laser_pose)
739 lasers_.push_back(createLaserObject());
740 lasers_update_.push_back(
true);
741 laser_index = frame_to_laser_.size();
743 geometry_msgs::msg::PoseStamped ident;
744 ident.header.frame_id = laser_scan_frame_id;
745 ident.header.stamp = rclcpp::Time();
746 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
748 tf_buffer_->transform(ident, laser_pose, base_frame_id_, transform_tolerance_);
749 }
catch (tf2::TransformException & e) {
751 get_logger(),
"Couldn't transform from %s to %s, "
752 "even though the message notifier is in use: (%s)",
753 laser_scan->header.frame_id.c_str(),
754 base_frame_id_.c_str(), e.what());
759 laser_pose_v.v[0] = laser_pose.pose.position.x;
760 laser_pose_v.v[1] = laser_pose.pose.position.y;
762 laser_pose_v.v[2] = 0;
763 lasers_[laser_index]->SetLaserPose(laser_pose_v);
764 frame_to_laser_[laser_scan->header.frame_id] = laser_index;
770 delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
771 delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
772 delta.v[2] = angleutils::angle_diff(pose.v[2], pf_odom_pose_.v[2]);
775 bool update = fabs(delta.v[0]) > d_thresh_ ||
776 fabs(delta.v[1]) > d_thresh_ ||
777 fabs(delta.v[2]) > a_thresh_;
778 update = update || force_update_;
782 bool AmclNode::updateFilter(
783 const int & laser_index,
784 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
788 ldata.laser = lasers_[laser_index];
789 ldata.range_count = laser_scan->ranges.size();
795 geometry_msgs::msg::QuaternionStamped min_q, inc_q;
796 min_q.header.stamp = laser_scan->header.stamp;
797 min_q.header.frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id);
798 min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min);
800 inc_q.header = min_q.header;
801 inc_q.quaternion = orientationAroundZAxis(laser_scan->angle_min + laser_scan->angle_increment);
803 tf_buffer_->transform(min_q, min_q, base_frame_id_);
804 tf_buffer_->transform(inc_q, inc_q, base_frame_id_);
805 }
catch (tf2::TransformException & e) {
807 get_logger(),
"Unable to transform min/max laser angles into base frame: %s",
811 double angle_min = tf2::getYaw(min_q.quaternion);
812 double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
815 angle_increment = fmod(angle_increment + 5 * M_PI, 2 * M_PI) - M_PI;
818 get_logger(),
"Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
822 if (laser_max_range_ > 0.0) {
823 ldata.range_max = std::min(laser_scan->range_max,
static_cast<float>(laser_max_range_));
825 ldata.range_max = laser_scan->range_max;
828 if (laser_min_range_ > 0.0) {
829 range_min = std::max(laser_scan->range_min,
static_cast<float>(laser_min_range_));
831 range_min = laser_scan->range_min;
835 ldata.ranges =
new double[ldata.range_count][2];
836 for (
int i = 0; i < ldata.range_count; i++) {
839 if (laser_scan->ranges[i] <= range_min) {
840 ldata.ranges[i][0] = ldata.range_max;
842 ldata.ranges[i][0] = laser_scan->ranges[i];
845 ldata.ranges[i][1] = angle_min +
846 (i * angle_increment);
849 lasers_update_[laser_index] =
false;
850 pf_odom_pose_ = pose;
858 if (!initial_pose_is_known_) {
return;}
859 auto cloud_with_weights_msg = std::make_unique<nav2_msgs::msg::ParticleCloud>();
860 cloud_with_weights_msg->header.stamp = this->now();
861 cloud_with_weights_msg->header.frame_id = global_frame_id_;
862 cloud_with_weights_msg->particles.resize(set->sample_count);
864 for (
int i = 0; i < set->sample_count; i++) {
865 cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
866 cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
867 cloud_with_weights_msg->particles[i].pose.position.z = 0;
868 cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
869 set->samples[i].pose.v[2]);
870 cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
873 particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
877 AmclNode::getMaxWeightHyp(
878 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
879 int & max_weight_hyp)
882 double max_weight = 0.0;
883 hyps.resize(pf_->sets[pf_->current_set].cluster_count);
884 for (
int hyp_count = 0;
885 hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
890 if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) {
891 RCLCPP_ERROR(get_logger(),
"Couldn't get stats on cluster %d", hyp_count);
895 hyps[hyp_count].weight = weight;
896 hyps[hyp_count].pf_pose_mean = pose_mean;
897 hyps[hyp_count].pf_pose_cov = pose_cov;
899 if (hyps[hyp_count].weight > max_weight) {
900 max_weight = hyps[hyp_count].weight;
901 max_weight_hyp = hyp_count;
905 if (max_weight > 0.0) {
907 get_logger(),
"Max weight pose: %.3f %.3f %.3f",
908 hyps[max_weight_hyp].pf_pose_mean.v[0],
909 hyps[max_weight_hyp].pf_pose_mean.v[1],
910 hyps[max_weight_hyp].pf_pose_mean.v[2]);
912 max_weight_hyps = hyps[max_weight_hyp];
919 AmclNode::publishAmclPose(
920 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
921 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
924 if (!initial_pose_is_known_) {
925 if (checkElapsedTime(2s, last_time_printed_msg_)) {
927 get_logger(),
"AMCL cannot publish a pose or update the transform. "
928 "Please set the initial pose...");
929 last_time_printed_msg_ = now();
934 auto p = std::make_unique<geometry_msgs::msg::PoseWithCovarianceStamped>();
936 p->header.frame_id = global_frame_id_;
937 p->header.stamp = laser_scan->header.stamp;
939 p->pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
940 p->pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
941 p->pose.pose.orientation = orientationAroundZAxis(hyps[max_weight_hyp].pf_pose_mean.v[2]);
944 for (
int i = 0; i < 2; i++) {
945 for (
int j = 0; j < 2; j++) {
949 p->pose.covariance[6 * i + j] = set->cov.m[i][j];
952 p->pose.covariance[6 * 5 + 5] = set->cov.m[2][2];
954 for (
auto covariance_value : p->pose.covariance) {
955 temp += covariance_value;
957 temp += p->pose.pose.position.x + p->pose.pose.position.y;
958 if (!std::isnan(temp)) {
959 RCLCPP_DEBUG(get_logger(),
"Publishing pose");
960 last_published_pose_ = *p;
961 first_pose_sent_ =
true;
962 pose_pub_->publish(std::move(p));
965 get_logger(),
"AMCL covariance or pose is NaN, likely due to an invalid "
966 "configuration or faulty sensor measurements! Pose is not available!");
970 get_logger(),
"New pose: %6.3f %6.3f %6.3f",
971 hyps[max_weight_hyp].pf_pose_mean.v[0],
972 hyps[max_weight_hyp].pf_pose_mean.v[1],
973 hyps[max_weight_hyp].pf_pose_mean.v[2]);
977 AmclNode::calculateMaptoOdomTransform(
978 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
979 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
982 geometry_msgs::msg::PoseStamped odom_to_map;
985 q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
986 tf2::Transform tmp_tf(q, tf2::Vector3(
987 hyps[max_weight_hyp].pf_pose_mean.v[0],
988 hyps[max_weight_hyp].pf_pose_mean.v[1],
991 geometry_msgs::msg::PoseStamped tmp_tf_stamped;
992 tmp_tf_stamped.header.frame_id = base_frame_id_;
993 tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
994 tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose);
996 tf_buffer_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_);
997 }
catch (tf2::TransformException & e) {
998 RCLCPP_DEBUG(get_logger(),
"Failed to subtract base to odom transform: (%s)", e.what());
1002 tf2::impl::Converter<true, false>::convert(odom_to_map.pose, latest_tf_);
1003 latest_tf_valid_ =
true;
1007 AmclNode::sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration)
1010 if (!initial_pose_is_known_) {
return;}
1011 geometry_msgs::msg::TransformStamped tmp_tf_stamped;
1012 tmp_tf_stamped.header.frame_id = global_frame_id_;
1013 tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_expiration);
1014 tmp_tf_stamped.child_frame_id = odom_frame_id_;
1015 tf2::impl::Converter<false, true>::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
1016 tf_broadcaster_->sendTransform(tmp_tf_stamped);
1020 AmclNode::createLaserObject()
1022 RCLCPP_INFO(get_logger(),
"createLaserObject");
1024 if (sensor_model_type_ ==
"beam") {
1026 z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_,
1027 0.0, max_beams_, map_);
1030 if (sensor_model_type_ ==
"likelihood_field_prob") {
1032 z_hit_, z_rand_, sigma_hit_,
1033 laser_likelihood_max_dist_, do_beamskip_, beam_skip_distance_, beam_skip_threshold_,
1034 beam_skip_error_threshold_, max_beams_, map_);
1038 z_hit_, z_rand_, sigma_hit_,
1039 laser_likelihood_max_dist_, max_beams_, map_);
1043 AmclNode::initParameters()
1045 double save_pose_rate;
1048 get_parameter(
"alpha1", alpha1_);
1049 get_parameter(
"alpha2", alpha2_);
1050 get_parameter(
"alpha3", alpha3_);
1051 get_parameter(
"alpha4", alpha4_);
1052 get_parameter(
"alpha5", alpha5_);
1053 get_parameter(
"base_frame_id", base_frame_id_);
1054 get_parameter(
"beam_skip_distance", beam_skip_distance_);
1055 get_parameter(
"beam_skip_error_threshold", beam_skip_error_threshold_);
1056 get_parameter(
"beam_skip_threshold", beam_skip_threshold_);
1057 get_parameter(
"do_beamskip", do_beamskip_);
1058 get_parameter(
"global_frame_id", global_frame_id_);
1059 get_parameter(
"lambda_short", lambda_short_);
1060 get_parameter(
"laser_likelihood_max_dist", laser_likelihood_max_dist_);
1061 get_parameter(
"laser_max_range", laser_max_range_);
1062 get_parameter(
"laser_min_range", laser_min_range_);
1063 get_parameter(
"laser_model_type", sensor_model_type_);
1064 get_parameter(
"set_initial_pose", set_initial_pose_);
1065 get_parameter(
"initial_pose.x", initial_pose_x_);
1066 get_parameter(
"initial_pose.y", initial_pose_y_);
1067 get_parameter(
"initial_pose.z", initial_pose_z_);
1068 get_parameter(
"initial_pose.yaw", initial_pose_yaw_);
1069 get_parameter(
"max_beams", max_beams_);
1070 get_parameter(
"max_particles", max_particles_);
1071 get_parameter(
"min_particles", min_particles_);
1072 get_parameter(
"odom_frame_id", odom_frame_id_);
1073 get_parameter(
"pf_err", pf_err_);
1074 get_parameter(
"pf_z", pf_z_);
1075 get_parameter(
"recovery_alpha_fast", alpha_fast_);
1076 get_parameter(
"recovery_alpha_slow", alpha_slow_);
1077 get_parameter(
"resample_interval", resample_interval_);
1078 get_parameter(
"robot_model_type", robot_model_type_);
1079 get_parameter(
"save_pose_rate", save_pose_rate);
1080 get_parameter(
"sigma_hit", sigma_hit_);
1081 get_parameter(
"tf_broadcast", tf_broadcast_);
1082 get_parameter(
"transform_tolerance", tmp_tol);
1083 get_parameter(
"update_min_a", a_thresh_);
1084 get_parameter(
"update_min_d", d_thresh_);
1085 get_parameter(
"z_hit", z_hit_);
1086 get_parameter(
"z_max", z_max_);
1087 get_parameter(
"z_rand", z_rand_);
1088 get_parameter(
"z_short", z_short_);
1089 get_parameter(
"first_map_only", first_map_only_);
1090 get_parameter(
"always_reset_initial_pose", always_reset_initial_pose_);
1091 get_parameter(
"scan_topic", scan_topic_);
1092 get_parameter(
"map_topic", map_topic_);
1094 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
1095 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
1097 odom_frame_id_ = nav2_util::strip_leading_slash(odom_frame_id_);
1098 base_frame_id_ = nav2_util::strip_leading_slash(base_frame_id_);
1099 global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_);
1101 last_time_printed_msg_ = now();
1104 if (laser_likelihood_max_dist_ < 0) {
1106 get_logger(),
"You've set laser_likelihood_max_dist to be negative,"
1107 " this isn't allowed so it will be set to default value 2.0.");
1108 laser_likelihood_max_dist_ = 2.0;
1110 if (max_particles_ < 0) {
1112 get_logger(),
"You've set max_particles to be negative,"
1113 " this isn't allowed so it will be set to default value 2000.");
1114 max_particles_ = 2000;
1117 if (min_particles_ < 0) {
1119 get_logger(),
"You've set min_particles to be negative,"
1120 " this isn't allowed so it will be set to default value 500.");
1121 min_particles_ = 500;
1124 if (min_particles_ > max_particles_) {
1126 get_logger(),
"You've set min_particles to be greater than max particles,"
1127 " this isn't allowed so max_particles will be set to min_particles.");
1128 max_particles_ = min_particles_;
1131 if (resample_interval_ <= 0) {
1133 get_logger(),
"You've set resample_interval to be zero or negative,"
1134 " this isn't allowed so it will be set to default value to 1.");
1135 resample_interval_ = 1;
1138 if (always_reset_initial_pose_) {
1139 initial_pose_is_known_ =
false;
1147 rcl_interfaces::msg::SetParametersResult
1148 AmclNode::dynamicParametersCallback(
1149 std::vector<rclcpp::Parameter> parameters)
1151 std::lock_guard<std::recursive_mutex> cfl(mutex_);
1152 rcl_interfaces::msg::SetParametersResult result;
1153 double save_pose_rate;
1156 int max_particles = max_particles_;
1157 int min_particles = min_particles_;
1159 bool reinit_pf =
false;
1160 bool reinit_odom =
false;
1161 bool reinit_laser =
false;
1162 bool reinit_map =
false;
1164 for (
auto parameter : parameters) {
1165 const auto & param_type = parameter.get_type();
1166 const auto & param_name = parameter.get_name();
1168 if (param_type == ParameterType::PARAMETER_DOUBLE) {
1169 if (param_name ==
"alpha1") {
1170 alpha1_ = parameter.as_double();
1172 if (alpha1_ < 0.0) {
1174 get_logger(),
"You've set alpha1 to be negative,"
1175 " this isn't allowed, so the alpha1 will be set to be zero.");
1179 }
else if (param_name ==
"alpha2") {
1180 alpha2_ = parameter.as_double();
1182 if (alpha2_ < 0.0) {
1184 get_logger(),
"You've set alpha2 to be negative,"
1185 " this isn't allowed, so the alpha2 will be set to be zero.");
1189 }
else if (param_name ==
"alpha3") {
1190 alpha3_ = parameter.as_double();
1192 if (alpha3_ < 0.0) {
1194 get_logger(),
"You've set alpha3 to be negative,"
1195 " this isn't allowed, so the alpha3 will be set to be zero.");
1199 }
else if (param_name ==
"alpha4") {
1200 alpha4_ = parameter.as_double();
1202 if (alpha4_ < 0.0) {
1204 get_logger(),
"You've set alpha4 to be negative,"
1205 " this isn't allowed, so the alpha4 will be set to be zero.");
1209 }
else if (param_name ==
"alpha5") {
1210 alpha5_ = parameter.as_double();
1212 if (alpha5_ < 0.0) {
1214 get_logger(),
"You've set alpha5 to be negative,"
1215 " this isn't allowed, so the alpha5 will be set to be zero.");
1219 }
else if (param_name ==
"beam_skip_distance") {
1220 beam_skip_distance_ = parameter.as_double();
1221 reinit_laser =
true;
1222 }
else if (param_name ==
"beam_skip_error_threshold") {
1223 beam_skip_error_threshold_ = parameter.as_double();
1224 reinit_laser =
true;
1225 }
else if (param_name ==
"beam_skip_threshold") {
1226 beam_skip_threshold_ = parameter.as_double();
1227 reinit_laser =
true;
1228 }
else if (param_name ==
"lambda_short") {
1229 lambda_short_ = parameter.as_double();
1230 reinit_laser =
true;
1231 }
else if (param_name ==
"laser_likelihood_max_dist") {
1232 laser_likelihood_max_dist_ = parameter.as_double();
1233 reinit_laser =
true;
1234 }
else if (param_name ==
"laser_max_range") {
1235 laser_max_range_ = parameter.as_double();
1236 reinit_laser =
true;
1237 }
else if (param_name ==
"laser_min_range") {
1238 laser_min_range_ = parameter.as_double();
1239 reinit_laser =
true;
1240 }
else if (param_name ==
"pf_err") {
1241 pf_err_ = parameter.as_double();
1243 }
else if (param_name ==
"pf_z") {
1244 pf_z_ = parameter.as_double();
1246 }
else if (param_name ==
"recovery_alpha_fast") {
1247 alpha_fast_ = parameter.as_double();
1249 }
else if (param_name ==
"recovery_alpha_slow") {
1250 alpha_slow_ = parameter.as_double();
1252 }
else if (param_name ==
"save_pose_rate") {
1253 save_pose_rate = parameter.as_double();
1254 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
1255 }
else if (param_name ==
"sigma_hit") {
1256 sigma_hit_ = parameter.as_double();
1257 reinit_laser =
true;
1258 }
else if (param_name ==
"transform_tolerance") {
1259 tmp_tol = parameter.as_double();
1260 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
1261 reinit_laser =
true;
1262 }
else if (param_name ==
"update_min_a") {
1263 a_thresh_ = parameter.as_double();
1264 }
else if (param_name ==
"update_min_d") {
1265 d_thresh_ = parameter.as_double();
1266 }
else if (param_name ==
"z_hit") {
1267 z_hit_ = parameter.as_double();
1268 reinit_laser =
true;
1269 }
else if (param_name ==
"z_max") {
1270 z_max_ = parameter.as_double();
1271 reinit_laser =
true;
1272 }
else if (param_name ==
"z_rand") {
1273 z_rand_ = parameter.as_double();
1274 reinit_laser =
true;
1275 }
else if (param_name ==
"z_short") {
1276 z_short_ = parameter.as_double();
1277 reinit_laser =
true;
1279 }
else if (param_type == ParameterType::PARAMETER_STRING) {
1280 if (param_name ==
"base_frame_id") {
1281 base_frame_id_ = parameter.as_string();
1282 }
else if (param_name ==
"global_frame_id") {
1283 global_frame_id_ = parameter.as_string();
1284 }
else if (param_name ==
"map_topic") {
1285 map_topic_ = parameter.as_string();
1287 }
else if (param_name ==
"laser_model_type") {
1288 sensor_model_type_ = parameter.as_string();
1289 reinit_laser =
true;
1290 }
else if (param_name ==
"odom_frame_id") {
1291 odom_frame_id_ = parameter.as_string();
1292 reinit_laser =
true;
1293 }
else if (param_name ==
"scan_topic") {
1294 scan_topic_ = parameter.as_string();
1295 reinit_laser =
true;
1296 }
else if (param_name ==
"robot_model_type") {
1297 robot_model_type_ = parameter.as_string();
1300 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
1301 if (param_name ==
"do_beamskip") {
1302 do_beamskip_ = parameter.as_bool();
1303 reinit_laser =
true;
1304 }
else if (param_name ==
"tf_broadcast") {
1305 tf_broadcast_ = parameter.as_bool();
1306 }
else if (param_name ==
"set_initial_pose") {
1307 set_initial_pose_ = parameter.as_bool();
1308 }
else if (param_name ==
"first_map_only") {
1309 first_map_only_ = parameter.as_bool();
1311 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
1312 if (param_name ==
"max_beams") {
1313 max_beams_ = parameter.as_int();
1314 reinit_laser =
true;
1315 }
else if (param_name ==
"max_particles") {
1316 max_particles_ = parameter.as_int();
1318 }
else if (param_name ==
"min_particles") {
1319 min_particles_ = parameter.as_int();
1321 }
else if (param_name ==
"resample_interval") {
1322 resample_interval_ = parameter.as_int();
1328 if (min_particles_ > max_particles_) {
1331 "You've set min_particles to be greater than max particles,"
1332 " this isn't allowed.");
1334 max_particles_ = max_particles;
1335 min_particles_ = min_particles;
1336 result.successful =
false;
1346 initParticleFilter();
1351 motion_model_.reset();
1358 lasers_update_.clear();
1359 frame_to_laser_.clear();
1360 laser_scan_connection_.disconnect();
1361 laser_scan_filter_.reset();
1362 laser_scan_sub_.reset();
1364 initMessageFilters();
1370 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1371 map_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
1372 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1));
1375 result.successful =
true;
1380 AmclNode::mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
1382 RCLCPP_DEBUG(get_logger(),
"AmclNode: A new map was received.");
1383 if (!nav2_util::validateMsg(*msg)) {
1384 RCLCPP_ERROR(get_logger(),
"Received map message is malformed. Rejecting.");
1387 if (first_map_only_ && first_map_received_) {
1390 handleMapMessage(*msg);
1391 first_map_received_ =
true;
1395 AmclNode::handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg)
1397 std::lock_guard<std::recursive_mutex> cfl(mutex_);
1400 get_logger(),
"Received a %d X %d map @ %.3f m/pix",
1403 msg.info.resolution);
1404 if (msg.header.frame_id != global_frame_id_) {
1406 get_logger(),
"Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could"
1407 " cause issues with reading published topics",
1408 msg.header.frame_id.c_str(),
1409 global_frame_id_.c_str());
1411 freeMapDependentMemory();
1412 map_ = convertMap(msg);
1414 #if NEW_UNIFORM_SAMPLING
1415 createFreeSpaceVector();
1420 AmclNode::createFreeSpaceVector()
1423 free_space_indices.resize(0);
1424 for (
int i = 0; i < map_->size_x; i++) {
1425 for (
int j = 0; j < map_->size_y; j++) {
1426 if (map_->cells[MAP_INDEX(map_, i, j)].occ_state == -1) {
1427 free_space_indices.push_back(std::make_pair(i, j));
1434 AmclNode::freeMapDependentMemory()
1444 lasers_update_.clear();
1445 frame_to_laser_.clear();
1451 AmclNode::convertMap(
const nav_msgs::msg::OccupancyGrid & map_msg)
1453 map_t * map = map_alloc();
1455 map->size_x = map_msg.info.width;
1456 map->size_y = map_msg.info.height;
1457 map->scale = map_msg.info.resolution;
1458 map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
1459 map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
1465 for (
int i = 0; i < map->size_x * map->size_y; i++) {
1466 if (map_msg.data[i] == 0) {
1467 map->cells[i].occ_state = -1;
1468 }
else if (map_msg.data[i] == 100) {
1469 map->cells[i].occ_state = +1;
1471 map->cells[i].occ_state = 0;
1479 AmclNode::initTransforms()
1481 RCLCPP_INFO(get_logger(),
"initTransforms");
1484 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
1485 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
1486 get_node_base_interface(),
1487 get_node_timers_interface(),
1489 tf_buffer_->setCreateTimerInterface(timer_interface);
1490 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
1491 tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
1493 sent_first_transform_ =
false;
1494 latest_tf_valid_ =
false;
1495 latest_tf_ = tf2::Transform::getIdentity();
1499 AmclNode::initMessageFilters()
1501 auto sub_opt = rclcpp::SubscriptionOptions();
1502 sub_opt.callback_group = callback_group_;
1503 laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
1504 rclcpp_lifecycle::LifecycleNode>>(
1505 shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt);
1507 laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
1508 *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
1509 get_node_logging_interface(),
1510 get_node_clock_interface(),
1511 transform_tolerance_);
1514 laser_scan_connection_ = laser_scan_filter_->registerCallback(
1516 &AmclNode::laserReceived,
1517 this, std::placeholders::_1));
1521 AmclNode::initPubSub()
1523 RCLCPP_INFO(get_logger(),
"initPubSub");
1525 particle_cloud_pub_ = create_publisher<nav2_msgs::msg::ParticleCloud>(
1527 rclcpp::SensorDataQoS());
1529 pose_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
1531 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
1533 initial_pose_sub_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
1534 "initialpose", rclcpp::SystemDefaultsQoS(),
1535 std::bind(&AmclNode::initialPoseReceived,
this, std::placeholders::_1));
1537 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1538 map_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
1539 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1));
1541 RCLCPP_INFO(get_logger(),
"Subscribed to map topic.");
1545 AmclNode::initServices()
1547 global_loc_srv_ = create_service<std_srvs::srv::Empty>(
1548 "reinitialize_global_localization",
1549 std::bind(&AmclNode::globalLocalizationCallback,
this, _1, _2, _3));
1551 initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
1553 std::bind(&AmclNode::initialPoseReceivedSrv,
this, _1, _2, _3));
1555 nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
1556 "request_nomotion_update",
1557 std::bind(&AmclNode::nomotionUpdateCallback,
this, _1, _2, _3));
1561 AmclNode::initOdometry()
1567 init_pose_[0] = last_published_pose_.pose.pose.position.x;
1568 init_pose_[1] = last_published_pose_.pose.pose.position.y;
1569 init_pose_[2] = tf2::getYaw(last_published_pose_.pose.pose.orientation);
1571 if (!initial_pose_is_known_) {
1572 init_cov_[0] = 0.5 * 0.5;
1573 init_cov_[1] = 0.5 * 0.5;
1574 init_cov_[2] = (M_PI / 12.0) * (M_PI / 12.0);
1576 init_cov_[0] = last_published_pose_.pose.covariance[0];
1577 init_cov_[1] = last_published_pose_.pose.covariance[7];
1578 init_cov_[2] = last_published_pose_.pose.covariance[35];
1581 motion_model_ = plugin_loader_.createSharedInstance(robot_model_type_);
1582 motion_model_->initialize(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
1584 latest_odom_pose_ = geometry_msgs::msg::PoseStamped();
1588 AmclNode::initParticleFilter()
1592 min_particles_, max_particles_, alpha_slow_, alpha_fast_,
1593 (pf_init_model_fn_t)AmclNode::uniformPoseGenerator);
1594 pf_->pop_err = pf_err_;
1599 pf_init_pose_mean.v[0] = init_pose_[0];
1600 pf_init_pose_mean.v[1] = init_pose_[1];
1601 pf_init_pose_mean.v[2] = init_pose_[2];
1604 pf_init_pose_cov.m[0][0] = init_cov_[0];
1605 pf_init_pose_cov.m[1][1] = init_cov_[1];
1606 pf_init_pose_cov.m[2][2] = init_cov_[2];
1608 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
1611 resample_count_ = 0;
1612 memset(&pf_odom_pose_, 0,
sizeof(pf_odom_pose_));
1616 AmclNode::initLaserScan()
1618 scan_error_count_ = 0;
1619 last_laser_received_ts_ = rclcpp::Time(0);
1624 #include "rclcpp_components/register_node_macro.hpp"