23 #include "nav2_amcl/amcl_node.hpp"
31 #include "nav2_amcl/angleutils.hpp"
32 #include "nav2_util/geometry_utils.hpp"
33 #include "nav2_amcl/pf/pf.hpp"
34 #include "nav2_util/string_utils.hpp"
35 #include "nav2_amcl/sensors/laser/laser.hpp"
36 #include "rclcpp/node_options.hpp"
37 #include "tf2/convert.hpp"
38 #include "tf2/utils.hpp"
39 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
40 #include "tf2/LinearMath/Transform.hpp"
41 #include "tf2_ros/buffer.hpp"
42 #include "tf2_ros/message_filter.hpp"
43 #include "tf2_ros/transform_broadcaster.hpp"
44 #include "tf2_ros/transform_listener.hpp"
45 #include "tf2_ros/create_timer_ros.hpp"
47 #include "nav2_amcl/portable_utils.hpp"
48 #include "nav2_ros_common/validate_messages.hpp"
50 using rcl_interfaces::msg::ParameterType;
51 using namespace std::chrono_literals;
55 using nav2_util::geometry_utils::orientationAroundZAxis;
57 AmclNode::AmclNode(
const rclcpp::NodeOptions & options)
58 : nav2::LifecycleNode(
"amcl",
"", options)
60 RCLCPP_INFO(get_logger(),
"Creating");
68 AmclNode::on_configure(
const rclcpp_lifecycle::State & )
70 RCLCPP_INFO(get_logger(),
"Configuring");
71 callback_group_ = create_callback_group(
72 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
81 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
82 executor_->add_callback_group(callback_group_, get_node_base_interface());
83 executor_thread_ = std::make_unique<nav2::NodeThread>(executor_);
84 return nav2::CallbackReturn::SUCCESS;
88 AmclNode::on_activate(
const rclcpp_lifecycle::State & )
90 RCLCPP_INFO(get_logger(),
"Activating");
93 pose_pub_->on_activate();
94 particle_cloud_pub_->on_activate();
96 first_pose_sent_ =
false;
102 if (set_initial_pose_) {
103 auto msg = std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>();
105 msg->header.stamp = now();
106 msg->header.frame_id = global_frame_id_;
107 msg->pose.pose.position.x = initial_pose_x_;
108 msg->pose.pose.position.y = initial_pose_y_;
109 msg->pose.pose.position.z = initial_pose_z_;
110 msg->pose.pose.orientation = orientationAroundZAxis(initial_pose_yaw_);
112 initialPoseReceived(msg);
113 }
else if (init_pose_received_on_inactive) {
114 handleInitialPose(last_published_pose_);
117 auto node = shared_from_this();
119 dyn_params_handler_ = node->add_on_set_parameters_callback(
121 &AmclNode::dynamicParametersCallback,
122 this, std::placeholders::_1));
127 return nav2::CallbackReturn::SUCCESS;
131 AmclNode::on_deactivate(
const rclcpp_lifecycle::State & )
133 RCLCPP_INFO(get_logger(),
"Deactivating");
138 pose_pub_->on_deactivate();
139 particle_cloud_pub_->on_deactivate();
142 remove_on_set_parameters_callback(dyn_params_handler_.get());
143 dyn_params_handler_.reset();
148 return nav2::CallbackReturn::SUCCESS;
152 AmclNode::on_cleanup(
const rclcpp_lifecycle::State & )
154 RCLCPP_INFO(get_logger(),
"Cleaning up");
156 executor_thread_.reset();
160 global_loc_srv_.reset();
161 initial_guess_srv_.reset();
162 nomotion_update_srv_.reset();
163 initial_pose_sub_.reset();
164 laser_scan_connection_.disconnect();
165 tf_listener_.reset();
166 laser_scan_filter_.reset();
167 laser_scan_sub_.reset();
175 first_map_received_ =
false;
176 free_space_indices.resize(0);
179 tf_broadcaster_.reset();
184 particle_cloud_pub_.reset();
187 motion_model_.reset();
195 lasers_update_.clear();
196 frame_to_laser_.clear();
197 force_update_ =
true;
199 if (set_initial_pose_) {
203 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.x)));
207 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.y)));
211 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.z)));
215 rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation))));
218 return nav2::CallbackReturn::SUCCESS;
222 AmclNode::on_shutdown(
const rclcpp_lifecycle::State & )
224 RCLCPP_INFO(get_logger(),
"Shutting down");
225 return nav2::CallbackReturn::SUCCESS;
229 AmclNode::checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time)
231 rclcpp::Duration elapsed_time = now() - last_time;
232 if (elapsed_time.nanoseconds() * 1e-9 > check_interval.count()) {
238 #if NEW_UNIFORM_SAMPLING
239 std::vector<AmclNode::Point2D> AmclNode::free_space_indices;
243 AmclNode::getOdomPose(
244 geometry_msgs::msg::PoseStamped & odom_pose,
245 double & x,
double & y,
double & yaw,
246 const rclcpp::Time & sensor_timestamp,
const std::string & frame_id)
249 geometry_msgs::msg::PoseStamped ident;
250 ident.header.frame_id = frame_id;
251 ident.header.stamp = sensor_timestamp;
252 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
255 tf_buffer_->transform(ident, odom_pose, odom_frame_id_);
256 }
catch (tf2::TransformException & e) {
258 if (scan_error_count_ % 20 == 0) {
260 get_logger(),
"(%d) consecutive laser scan transforms failed: (%s)", scan_error_count_,
266 scan_error_count_ = 0;
267 x = odom_pose.pose.position.x;
268 y = odom_pose.pose.position.y;
269 yaw = tf2::getYaw(odom_pose.pose.orientation);
275 AmclNode::uniformPoseGenerator(
void * arg)
279 #if NEW_UNIFORM_SAMPLING
280 unsigned int rand_index = drand48() * free_space_indices.size();
281 AmclNode::Point2D free_point = free_space_indices[rand_index];
283 p.v[0] = MAP_WXGX(map, free_point.x);
284 p.v[1] = MAP_WYGY(map, free_point.y);
285 p.v[2] = drand48() * 2 * M_PI - M_PI;
287 double min_x, max_x, min_y, max_y;
289 min_x = (map->size_x * map->scale) / 2.0 - map->origin_x;
290 max_x = (map->size_x * map->scale) / 2.0 + map->origin_x;
291 min_y = (map->size_y * map->scale) / 2.0 - map->origin_y;
292 max_y = (map->size_y * map->scale) / 2.0 + map->origin_y;
296 RCLCPP_DEBUG(get_logger(),
"Generating new uniform sample");
298 p.v[0] = min_x + drand48() * (max_x - min_x);
299 p.v[1] = min_y + drand48() * (max_y - min_y);
300 p.v[2] = drand48() * 2 * M_PI - M_PI;
303 i = MAP_GXWX(map, p.v[0]);
304 j = MAP_GYWY(map, p.v[1]);
305 if (MAP_VALID(map, i, j) && (map->cells[MAP_INDEX(map, i, j)].occ_state == -1)) {
314 AmclNode::globalLocalizationCallback(
315 const std::shared_ptr<rmw_request_id_t>,
316 const std::shared_ptr<std_srvs::srv::Empty::Request>,
317 std::shared_ptr<std_srvs::srv::Empty::Response>)
319 std::lock_guard<std::recursive_mutex> cfl(mutex_);
321 RCLCPP_INFO(get_logger(),
"Initializing with uniform distribution");
324 pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
325 reinterpret_cast<void *
>(map_));
326 RCLCPP_INFO(get_logger(),
"Global initialisation done!");
327 initial_pose_is_known_ =
true;
332 AmclNode::initialPoseReceivedSrv(
333 const std::shared_ptr<rmw_request_id_t>,
334 const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
335 std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>)
337 initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
342 AmclNode::nomotionUpdateCallback(
343 const std::shared_ptr<rmw_request_id_t>,
344 const std::shared_ptr<std_srvs::srv::Empty::Request>,
345 std::shared_ptr<std_srvs::srv::Empty::Response>)
347 RCLCPP_INFO(get_logger(),
"Requesting no-motion update");
348 force_update_ =
true;
352 AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
354 std::lock_guard<std::recursive_mutex> cfl(mutex_);
356 RCLCPP_INFO(get_logger(),
"initialPoseReceived");
358 if (!nav2::validateMsg(*msg)) {
359 RCLCPP_ERROR(get_logger(),
"Received initialpose message is malformed. Rejecting.");
362 if (msg->header.frame_id != global_frame_id_) {
365 "Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
366 msg->header.frame_id.c_str(),
367 global_frame_id_.c_str());
370 if (first_map_received_ && (abs(msg->pose.pose.position.x) > map_->size_x ||
371 abs(msg->pose.pose.position.y) > map_->size_y))
374 get_logger(),
"Received initialpose from message is out of the size of map. Rejecting.");
379 last_published_pose_ = *msg;
382 init_pose_received_on_inactive =
true;
384 get_logger(),
"Received initial pose request, "
385 "but AMCL is not yet in the active state");
388 handleInitialPose(*msg);
392 AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
394 std::lock_guard<std::recursive_mutex> cfl(mutex_);
397 geometry_msgs::msg::TransformStamped tx_odom;
399 rclcpp::Time rclcpp_time = now();
400 tf2::TimePoint tf2_time(std::chrono::nanoseconds(rclcpp_time.nanoseconds()));
403 tx_odom = tf_buffer_->lookupTransform(
404 base_frame_id_, tf2_ros::fromMsg(msg.header.stamp),
405 base_frame_id_, tf2_time, odom_frame_id_);
406 }
catch (tf2::TransformException & e) {
411 if (sent_first_transform_) {
412 RCLCPP_WARN(get_logger(),
"Failed to transform initial pose in time (%s)", e.what());
414 tf2::impl::Converter<false, true>::convert(tf2::Transform::getIdentity(), tx_odom.transform);
417 tf2::Transform tx_odom_tf2;
418 tf2::impl::Converter<true, false>::convert(tx_odom.transform, tx_odom_tf2);
420 tf2::Transform pose_old;
421 tf2::impl::Converter<true, false>::convert(msg.pose.pose, pose_old);
423 tf2::Transform pose_new = pose_old * tx_odom_tf2;
428 get_logger(),
"Setting pose (%.6f): %.3f %.3f %.3f",
429 now().nanoseconds() * 1e-9,
430 pose_new.getOrigin().x(),
431 pose_new.getOrigin().y(),
432 tf2::getYaw(pose_new.getRotation()));
436 pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
437 pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
438 pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
442 for (
int i = 0; i < 2; i++) {
443 for (
int j = 0; j < 2; j++) {
444 pf_init_pose_cov.m[i][j] = msg.pose.covariance[6 * i + j];
448 pf_init_pose_cov.m[2][2] = msg.pose.covariance[6 * 5 + 5];
450 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
452 init_pose_received_on_inactive =
false;
453 initial_pose_is_known_ =
true;
457 AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
459 std::lock_guard<std::recursive_mutex> cfl(mutex_);
463 if (!active_) {
return;}
464 if (!first_map_received_) {
465 if (checkElapsedTime(2s, last_time_printed_msg_)) {
466 RCLCPP_WARN(get_logger(),
"Waiting for map....");
467 last_time_printed_msg_ = now();
472 std::string laser_scan_frame_id = laser_scan->header.frame_id;
473 last_laser_received_ts_ = now();
474 int laser_index = -1;
475 geometry_msgs::msg::PoseStamped laser_pose;
478 if (frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) {
479 if (!addNewScanner(laser_index, laser_scan, laser_scan_frame_id, laser_pose)) {
484 laser_index = frame_to_laser_[laser_scan->header.frame_id];
490 latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
491 laser_scan->header.stamp, base_frame_id_))
493 RCLCPP_ERROR(get_logger(),
"Couldn't determine robot's pose associated with laser scan");
498 bool force_publication =
false;
501 pf_odom_pose_ = pose;
504 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
505 lasers_update_[i] =
true;
508 force_publication =
true;
512 if (shouldUpdateFilter(pose, delta)) {
513 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
514 lasers_update_[i] =
true;
517 if (lasers_update_[laser_index]) {
518 motion_model_->odometryUpdate(pf_, pose, delta);
520 force_update_ =
false;
523 bool resampled =
false;
526 if (lasers_update_[laser_index]) {
527 updateFilter(laser_index, laser_scan, pose);
530 if (!(++resample_count_ % resample_interval_)) {
531 pf_update_resample(pf_,
reinterpret_cast<void *
>(map_));
536 RCLCPP_DEBUG(get_logger(),
"Num samples: %d\n", set->sample_count);
538 if (!force_update_) {
539 publishParticleCloud(set);
542 if (resampled || force_publication || !first_pose_sent_) {
543 amcl_hyp_t max_weight_hyps;
544 std::vector<amcl_hyp_t> hyps;
545 int max_weight_hyp = -1;
546 if (getMaxWeightHyp(hyps, max_weight_hyps, max_weight_hyp)) {
547 publishAmclPose(laser_scan, hyps, max_weight_hyp);
548 calculateMaptoOdomTransform(laser_scan, hyps, max_weight_hyp);
550 if (tf_broadcast_ ==
true) {
553 auto stamp = tf2_ros::fromMsg(laser_scan->header.stamp);
554 tf2::TimePoint transform_expiration = stamp + transform_tolerance_;
555 sendMapToOdomTransform(transform_expiration);
556 sent_first_transform_ =
true;
559 RCLCPP_ERROR(get_logger(),
"No pose!");
561 }
else if (latest_tf_valid_) {
562 if (tf_broadcast_ ==
true) {
565 tf2::TimePoint transform_expiration = tf2_ros::fromMsg(laser_scan->header.stamp) +
566 transform_tolerance_;
567 sendMapToOdomTransform(transform_expiration);
572 bool AmclNode::addNewScanner(
574 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
575 const std::string & laser_scan_frame_id,
576 geometry_msgs::msg::PoseStamped & laser_pose)
578 lasers_.push_back(createLaserObject());
579 lasers_update_.push_back(
true);
580 laser_index = frame_to_laser_.size();
582 geometry_msgs::msg::PoseStamped ident;
583 ident.header.frame_id = laser_scan_frame_id;
584 ident.header.stamp = rclcpp::Time();
585 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
587 tf_buffer_->transform(ident, laser_pose, base_frame_id_, transform_tolerance_);
588 }
catch (tf2::TransformException & e) {
590 get_logger(),
"Couldn't transform from %s to %s, "
591 "even though the message notifier is in use: (%s)",
592 laser_scan->header.frame_id.c_str(),
593 base_frame_id_.c_str(), e.what());
598 laser_pose_v.v[0] = laser_pose.pose.position.x;
599 laser_pose_v.v[1] = laser_pose.pose.position.y;
601 laser_pose_v.v[2] = 0;
602 lasers_[laser_index]->SetLaserPose(laser_pose_v);
603 frame_to_laser_[laser_scan->header.frame_id] = laser_index;
609 delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
610 delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
611 delta.v[2] = angleutils::angle_diff(pose.v[2], pf_odom_pose_.v[2]);
614 bool update = fabs(delta.v[0]) > d_thresh_ ||
615 fabs(delta.v[1]) > d_thresh_ ||
616 fabs(delta.v[2]) > a_thresh_;
617 update = update || force_update_;
621 bool AmclNode::updateFilter(
622 const int & laser_index,
623 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
627 ldata.laser = lasers_[laser_index];
628 ldata.range_count = laser_scan->ranges.size();
634 geometry_msgs::msg::QuaternionStamped min_q, inc_q;
635 min_q.header.stamp = laser_scan->header.stamp;
636 min_q.header.frame_id = laser_scan->header.frame_id;
637 min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min);
639 inc_q.header = min_q.header;
640 inc_q.quaternion = orientationAroundZAxis(laser_scan->angle_min + laser_scan->angle_increment);
642 tf_buffer_->transform(min_q, min_q, base_frame_id_);
643 tf_buffer_->transform(inc_q, inc_q, base_frame_id_);
644 }
catch (tf2::TransformException & e) {
646 get_logger(),
"Unable to transform min/max laser angles into base frame: %s",
650 double angle_min = tf2::getYaw(min_q.quaternion);
651 double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
654 angle_increment = fmod(angle_increment + 5 * M_PI, 2 * M_PI) - M_PI;
657 get_logger(),
"Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
661 if (laser_scan->range_max <= 0.0) {
663 get_logger(),
"wrong range_max of laser_scan data: %f. The message could be malformed."
664 " Ignore this message and stop updating.",
665 laser_scan->range_max);
670 if (laser_max_range_ > 0.0) {
671 ldata.range_max = std::min(laser_scan->range_max,
static_cast<float>(laser_max_range_));
673 ldata.range_max = laser_scan->range_max;
676 if (laser_min_range_ > 0.0) {
677 range_min = std::max(laser_scan->range_min,
static_cast<float>(laser_min_range_));
679 range_min = laser_scan->range_min;
683 ldata.ranges =
new double[ldata.range_count][2];
684 for (
int i = 0; i < ldata.range_count; i++) {
687 if (laser_scan->ranges[i] <= range_min) {
688 ldata.ranges[i][0] = ldata.range_max;
690 ldata.ranges[i][0] = laser_scan->ranges[i];
693 ldata.ranges[i][1] = angle_min +
694 (i * angle_increment);
697 lasers_update_[laser_index] =
false;
698 pf_odom_pose_ = pose;
706 if (!initial_pose_is_known_) {
return;}
707 auto cloud_with_weights_msg = std::make_unique<nav2_msgs::msg::ParticleCloud>();
708 cloud_with_weights_msg->header.stamp = this->now();
709 cloud_with_weights_msg->header.frame_id = global_frame_id_;
710 cloud_with_weights_msg->particles.resize(set->sample_count);
712 for (
int i = 0; i < set->sample_count; i++) {
713 cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
714 cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
715 cloud_with_weights_msg->particles[i].pose.position.z = 0;
716 cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
717 set->samples[i].pose.v[2]);
718 cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
721 particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
725 AmclNode::getMaxWeightHyp(
726 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
727 int & max_weight_hyp)
730 double max_weight = 0.0;
731 hyps.resize(pf_->sets[pf_->current_set].cluster_count);
732 for (
int hyp_count = 0;
733 hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
738 if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) {
739 RCLCPP_ERROR(get_logger(),
"Couldn't get stats on cluster %d", hyp_count);
743 hyps[hyp_count].weight = weight;
744 hyps[hyp_count].pf_pose_mean = pose_mean;
745 hyps[hyp_count].pf_pose_cov = pose_cov;
747 if (hyps[hyp_count].weight > max_weight) {
748 max_weight = hyps[hyp_count].weight;
749 max_weight_hyp = hyp_count;
753 if (max_weight > 0.0) {
755 get_logger(),
"Max weight pose: %.3f %.3f %.3f",
756 hyps[max_weight_hyp].pf_pose_mean.v[0],
757 hyps[max_weight_hyp].pf_pose_mean.v[1],
758 hyps[max_weight_hyp].pf_pose_mean.v[2]);
760 max_weight_hyps = hyps[max_weight_hyp];
767 AmclNode::publishAmclPose(
768 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
769 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
772 if (!initial_pose_is_known_) {
773 if (checkElapsedTime(2s, last_time_printed_msg_)) {
775 get_logger(),
"AMCL cannot publish a pose or update the transform. "
776 "Please set the initial pose...");
777 last_time_printed_msg_ = now();
782 auto p = std::make_unique<geometry_msgs::msg::PoseWithCovarianceStamped>();
784 p->header.frame_id = global_frame_id_;
785 p->header.stamp = laser_scan->header.stamp;
787 p->pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
788 p->pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
789 p->pose.pose.orientation = orientationAroundZAxis(hyps[max_weight_hyp].pf_pose_mean.v[2]);
792 for (
int i = 0; i < 2; i++) {
793 for (
int j = 0; j < 2; j++) {
797 p->pose.covariance[6 * i + j] = set->cov.m[i][j];
800 p->pose.covariance[6 * 5 + 5] = set->cov.m[2][2];
802 for (
auto covariance_value : p->pose.covariance) {
803 temp += covariance_value;
805 temp += p->pose.pose.position.x + p->pose.pose.position.y;
806 if (!std::isnan(temp)) {
807 RCLCPP_DEBUG(get_logger(),
"Publishing pose");
808 last_published_pose_ = *p;
809 first_pose_sent_ =
true;
810 pose_pub_->publish(std::move(p));
813 get_logger(),
"AMCL covariance or pose is NaN, likely due to an invalid "
814 "configuration or faulty sensor measurements! Pose is not available!");
818 get_logger(),
"New pose: %6.3f %6.3f %6.3f",
819 hyps[max_weight_hyp].pf_pose_mean.v[0],
820 hyps[max_weight_hyp].pf_pose_mean.v[1],
821 hyps[max_weight_hyp].pf_pose_mean.v[2]);
825 AmclNode::calculateMaptoOdomTransform(
826 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
827 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
830 geometry_msgs::msg::PoseStamped odom_to_map;
833 q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
834 tf2::Transform tmp_tf(q, tf2::Vector3(
835 hyps[max_weight_hyp].pf_pose_mean.v[0],
836 hyps[max_weight_hyp].pf_pose_mean.v[1],
839 geometry_msgs::msg::PoseStamped tmp_tf_stamped;
840 tmp_tf_stamped.header.frame_id = base_frame_id_;
841 tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
842 tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose);
844 tf_buffer_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_);
845 }
catch (tf2::TransformException & e) {
846 RCLCPP_DEBUG(get_logger(),
"Failed to subtract base to odom transform: (%s)", e.what());
850 tf2::impl::Converter<true, false>::convert(odom_to_map.pose, latest_tf_);
851 latest_tf_valid_ =
true;
855 AmclNode::sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration)
858 if (!initial_pose_is_known_) {
return;}
859 geometry_msgs::msg::TransformStamped tmp_tf_stamped;
860 tmp_tf_stamped.header.frame_id = global_frame_id_;
861 tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_expiration);
862 tmp_tf_stamped.child_frame_id = odom_frame_id_;
863 tf2::impl::Converter<false, true>::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
864 tf_broadcaster_->sendTransform(tmp_tf_stamped);
868 AmclNode::createLaserObject()
870 RCLCPP_INFO(get_logger(),
"createLaserObject");
872 if (sensor_model_type_ ==
"beam") {
874 z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_,
875 0.0, max_beams_, map_);
878 if (sensor_model_type_ ==
"likelihood_field_prob") {
880 z_hit_, z_rand_, sigma_hit_,
881 laser_likelihood_max_dist_, do_beamskip_, beam_skip_distance_, beam_skip_threshold_,
882 beam_skip_error_threshold_, max_beams_, map_);
886 z_hit_, z_rand_, sigma_hit_,
887 laser_likelihood_max_dist_, max_beams_, map_);
891 AmclNode::initParameters()
893 double save_pose_rate;
896 alpha1_ = this->declare_or_get_parameter(
"alpha1", 0.2);
897 alpha2_ = this->declare_or_get_parameter(
"alpha2", 0.2);
898 alpha3_ = this->declare_or_get_parameter(
"alpha3", 0.2);
899 alpha4_ = this->declare_or_get_parameter(
"alpha4", 0.2);
900 alpha5_ = this->declare_or_get_parameter(
"alpha5", 0.2);
901 base_frame_id_ = this->declare_or_get_parameter(
"base_frame_id", std::string{
"base_footprint"});
902 beam_skip_distance_ = this->declare_or_get_parameter(
"beam_skip_distance", 0.5);
903 beam_skip_error_threshold_ = this->declare_or_get_parameter(
"beam_skip_error_threshold", 0.9);
904 beam_skip_threshold_ = this->declare_or_get_parameter(
"beam_skip_threshold", 0.3);
905 do_beamskip_ = this->declare_or_get_parameter(
"do_beamskip",
false);
906 global_frame_id_ = this->declare_or_get_parameter(
"global_frame_id", std::string{
"map"});
907 lambda_short_ = this->declare_or_get_parameter(
"lambda_short", 0.1);
908 laser_likelihood_max_dist_ = this->declare_or_get_parameter(
"laser_likelihood_max_dist", 2.0);
909 laser_max_range_ = this->declare_or_get_parameter(
"laser_max_range", 100.0);
910 laser_min_range_ = this->declare_or_get_parameter(
"laser_min_range", -1.0);
911 sensor_model_type_ = this->declare_or_get_parameter(
912 "laser_model_type", std::string{
"likelihood_field"});
913 set_initial_pose_ = this->declare_or_get_parameter(
"set_initial_pose",
false);
914 initial_pose_x_ = this->declare_or_get_parameter(
"initial_pose.x", 0.0);
915 initial_pose_y_ = this->declare_or_get_parameter(
"initial_pose.y", 0.0);
916 initial_pose_z_ = this->declare_or_get_parameter(
"initial_pose.z", 0.0);
917 initial_pose_yaw_ = this->declare_or_get_parameter(
"initial_pose.yaw", 0.0);
918 max_beams_ = this->declare_or_get_parameter(
"max_beams", 60);
919 max_particles_ = this->declare_or_get_parameter(
"max_particles", 2000);
920 min_particles_ = this->declare_or_get_parameter(
"min_particles", 500);
921 odom_frame_id_ = this->declare_or_get_parameter(
"odom_frame_id", std::string{
"odom"});
922 pf_err_ = this->declare_or_get_parameter(
"pf_err", 0.05);
923 pf_z_ = this->declare_or_get_parameter(
"pf_z", 0.99);
924 alpha_fast_ = this->declare_or_get_parameter(
"recovery_alpha_fast", 0.0);
925 alpha_slow_ = this->declare_or_get_parameter(
"recovery_alpha_slow", 0.0);
926 resample_interval_ = this->declare_or_get_parameter(
"resample_interval", 1);
927 robot_model_type_ = this->declare_or_get_parameter(
928 "robot_model_type", std::string{
"nav2_amcl::DifferentialMotionModel"});
929 save_pose_rate = this->declare_or_get_parameter(
"save_pose_rate", 0.5);
930 sigma_hit_ = this->declare_or_get_parameter(
"sigma_hit", 0.2);
931 tf_broadcast_ = this->declare_or_get_parameter(
"tf_broadcast",
true);
932 tmp_tol = this->declare_or_get_parameter(
"transform_tolerance", 1.0);
933 a_thresh_ = this->declare_or_get_parameter(
"update_min_a", 0.2);
934 d_thresh_ = this->declare_or_get_parameter(
"update_min_d", 0.25);
935 z_hit_ = this->declare_or_get_parameter(
"z_hit", 0.5);
936 z_max_ = this->declare_or_get_parameter(
"z_max", 0.05);
937 z_rand_ = this->declare_or_get_parameter(
"z_rand", 0.5);
938 z_short_ = this->declare_or_get_parameter(
"z_short", 0.05);
939 first_map_only_ = this->declare_or_get_parameter(
"first_map_only",
false);
940 always_reset_initial_pose_ = this->declare_or_get_parameter(
"always_reset_initial_pose",
false);
941 scan_topic_ = this->declare_or_get_parameter(
"scan_topic", std::string{
"scan"});
942 map_topic_ = this->declare_or_get_parameter(
"map_topic", std::string{
"map"});
943 freespace_downsampling_ = this->declare_or_get_parameter(
"freespace_downsampling",
false);
945 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
946 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
947 last_time_printed_msg_ = now();
950 if (laser_likelihood_max_dist_ < 0) {
952 get_logger(),
"You've set laser_likelihood_max_dist to be negative,"
953 " this isn't allowed so it will be set to default value 2.0.");
954 laser_likelihood_max_dist_ = 2.0;
956 if (max_particles_ < 0) {
958 get_logger(),
"You've set max_particles to be negative,"
959 " this isn't allowed so it will be set to default value 2000.");
960 max_particles_ = 2000;
963 if (min_particles_ < 0) {
965 get_logger(),
"You've set min_particles to be negative,"
966 " this isn't allowed so it will be set to default value 500.");
967 min_particles_ = 500;
970 if (min_particles_ > max_particles_) {
972 get_logger(),
"You've set min_particles to be greater than max particles,"
973 " this isn't allowed so max_particles will be set to min_particles.");
974 max_particles_ = min_particles_;
977 if (resample_interval_ <= 0) {
979 get_logger(),
"You've set resample_interval to be zero or negative,"
980 " this isn't allowed so it will be set to default value to 1.");
981 resample_interval_ = 1;
984 if (always_reset_initial_pose_) {
985 initial_pose_is_known_ =
false;
993 rcl_interfaces::msg::SetParametersResult
994 AmclNode::dynamicParametersCallback(
995 std::vector<rclcpp::Parameter> parameters)
997 std::lock_guard<std::recursive_mutex> cfl(mutex_);
998 rcl_interfaces::msg::SetParametersResult result;
999 double save_pose_rate;
1002 int max_particles = max_particles_;
1003 int min_particles = min_particles_;
1005 bool reinit_pf =
false;
1006 bool reinit_odom =
false;
1007 bool reinit_laser =
false;
1008 bool reinit_map =
false;
1010 for (
auto parameter : parameters) {
1011 const auto & param_type = parameter.get_type();
1012 const auto & param_name = parameter.get_name();
1013 if (param_name.find(
'.') != std::string::npos) {
1017 if (param_type == ParameterType::PARAMETER_DOUBLE) {
1018 if (param_name ==
"alpha1") {
1019 alpha1_ = parameter.as_double();
1021 if (alpha1_ < 0.0) {
1023 get_logger(),
"You've set alpha1 to be negative,"
1024 " this isn't allowed, so the alpha1 will be set to be zero.");
1028 }
else if (param_name ==
"alpha2") {
1029 alpha2_ = parameter.as_double();
1031 if (alpha2_ < 0.0) {
1033 get_logger(),
"You've set alpha2 to be negative,"
1034 " this isn't allowed, so the alpha2 will be set to be zero.");
1038 }
else if (param_name ==
"alpha3") {
1039 alpha3_ = parameter.as_double();
1041 if (alpha3_ < 0.0) {
1043 get_logger(),
"You've set alpha3 to be negative,"
1044 " this isn't allowed, so the alpha3 will be set to be zero.");
1048 }
else if (param_name ==
"alpha4") {
1049 alpha4_ = parameter.as_double();
1051 if (alpha4_ < 0.0) {
1053 get_logger(),
"You've set alpha4 to be negative,"
1054 " this isn't allowed, so the alpha4 will be set to be zero.");
1058 }
else if (param_name ==
"alpha5") {
1059 alpha5_ = parameter.as_double();
1061 if (alpha5_ < 0.0) {
1063 get_logger(),
"You've set alpha5 to be negative,"
1064 " this isn't allowed, so the alpha5 will be set to be zero.");
1068 }
else if (param_name ==
"beam_skip_distance") {
1069 beam_skip_distance_ = parameter.as_double();
1070 reinit_laser =
true;
1071 }
else if (param_name ==
"beam_skip_error_threshold") {
1072 beam_skip_error_threshold_ = parameter.as_double();
1073 reinit_laser =
true;
1074 }
else if (param_name ==
"beam_skip_threshold") {
1075 beam_skip_threshold_ = parameter.as_double();
1076 reinit_laser =
true;
1077 }
else if (param_name ==
"lambda_short") {
1078 lambda_short_ = parameter.as_double();
1079 reinit_laser =
true;
1080 }
else if (param_name ==
"laser_likelihood_max_dist") {
1081 laser_likelihood_max_dist_ = parameter.as_double();
1082 reinit_laser =
true;
1083 }
else if (param_name ==
"laser_max_range") {
1084 laser_max_range_ = parameter.as_double();
1085 reinit_laser =
true;
1086 }
else if (param_name ==
"laser_min_range") {
1087 laser_min_range_ = parameter.as_double();
1088 reinit_laser =
true;
1089 }
else if (param_name ==
"pf_err") {
1090 pf_err_ = parameter.as_double();
1092 }
else if (param_name ==
"pf_z") {
1093 pf_z_ = parameter.as_double();
1095 }
else if (param_name ==
"recovery_alpha_fast") {
1096 alpha_fast_ = parameter.as_double();
1098 }
else if (param_name ==
"recovery_alpha_slow") {
1099 alpha_slow_ = parameter.as_double();
1101 }
else if (param_name ==
"save_pose_rate") {
1102 save_pose_rate = parameter.as_double();
1103 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
1104 }
else if (param_name ==
"sigma_hit") {
1105 sigma_hit_ = parameter.as_double();
1106 reinit_laser =
true;
1107 }
else if (param_name ==
"transform_tolerance") {
1108 tmp_tol = parameter.as_double();
1109 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
1110 reinit_laser =
true;
1111 }
else if (param_name ==
"update_min_a") {
1112 a_thresh_ = parameter.as_double();
1113 }
else if (param_name ==
"update_min_d") {
1114 d_thresh_ = parameter.as_double();
1115 }
else if (param_name ==
"z_hit") {
1116 z_hit_ = parameter.as_double();
1117 reinit_laser =
true;
1118 }
else if (param_name ==
"z_max") {
1119 z_max_ = parameter.as_double();
1120 reinit_laser =
true;
1121 }
else if (param_name ==
"z_rand") {
1122 z_rand_ = parameter.as_double();
1123 reinit_laser =
true;
1124 }
else if (param_name ==
"z_short") {
1125 z_short_ = parameter.as_double();
1126 reinit_laser =
true;
1128 }
else if (param_type == ParameterType::PARAMETER_STRING) {
1129 if (param_name ==
"base_frame_id") {
1130 base_frame_id_ = parameter.as_string();
1131 }
else if (param_name ==
"global_frame_id") {
1132 global_frame_id_ = parameter.as_string();
1133 }
else if (param_name ==
"map_topic") {
1134 map_topic_ = parameter.as_string();
1136 }
else if (param_name ==
"laser_model_type") {
1137 sensor_model_type_ = parameter.as_string();
1138 reinit_laser =
true;
1139 }
else if (param_name ==
"odom_frame_id") {
1140 odom_frame_id_ = parameter.as_string();
1141 reinit_laser =
true;
1142 }
else if (param_name ==
"scan_topic") {
1143 scan_topic_ = parameter.as_string();
1144 reinit_laser =
true;
1145 }
else if (param_name ==
"robot_model_type") {
1146 robot_model_type_ = parameter.as_string();
1149 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
1150 if (param_name ==
"do_beamskip") {
1151 do_beamskip_ = parameter.as_bool();
1152 reinit_laser =
true;
1153 }
else if (param_name ==
"tf_broadcast") {
1154 tf_broadcast_ = parameter.as_bool();
1155 }
else if (param_name ==
"set_initial_pose") {
1156 set_initial_pose_ = parameter.as_bool();
1157 }
else if (param_name ==
"first_map_only") {
1158 first_map_only_ = parameter.as_bool();
1160 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
1161 if (param_name ==
"max_beams") {
1162 max_beams_ = parameter.as_int();
1163 reinit_laser =
true;
1164 }
else if (param_name ==
"max_particles") {
1165 max_particles_ = parameter.as_int();
1167 }
else if (param_name ==
"min_particles") {
1168 min_particles_ = parameter.as_int();
1170 }
else if (param_name ==
"resample_interval") {
1171 resample_interval_ = parameter.as_int();
1177 if (min_particles_ > max_particles_) {
1180 "You've set min_particles to be greater than max particles,"
1181 " this isn't allowed.");
1183 max_particles_ = max_particles;
1184 min_particles_ = min_particles;
1185 result.successful =
false;
1195 initParticleFilter();
1200 motion_model_.reset();
1207 lasers_update_.clear();
1208 frame_to_laser_.clear();
1209 laser_scan_connection_.disconnect();
1210 laser_scan_filter_.reset();
1211 laser_scan_sub_.reset();
1213 initMessageFilters();
1219 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1221 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1),
1225 result.successful =
true;
1230 AmclNode::mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
1232 RCLCPP_DEBUG(get_logger(),
"AmclNode: A new map was received.");
1233 if (!nav2::validateMsg(*msg)) {
1234 RCLCPP_ERROR(get_logger(),
"Received map message is malformed. Rejecting.");
1237 if (first_map_only_ && first_map_received_) {
1240 handleMapMessage(*msg);
1241 first_map_received_ =
true;
1245 AmclNode::handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg)
1247 std::lock_guard<std::recursive_mutex> cfl(mutex_);
1250 get_logger(),
"Received a %d X %d map @ %.3f m/pix",
1253 msg.info.resolution);
1254 if (msg.header.frame_id != global_frame_id_) {
1256 get_logger(),
"Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could"
1257 " cause issues with reading published topics",
1258 msg.header.frame_id.c_str(),
1259 global_frame_id_.c_str());
1261 freeMapDependentMemory();
1262 map_ = convertMap(msg);
1264 #if NEW_UNIFORM_SAMPLING
1265 createFreeSpaceVector();
1270 AmclNode::createFreeSpaceVector()
1272 int delta = freespace_downsampling_ ? 2 : 1;
1274 free_space_indices.resize(0);
1275 for (
int i = 0; i < map_->size_x; i += delta) {
1276 for (
int j = 0; j < map_->size_y; j += delta) {
1277 if (map_->cells[MAP_INDEX(map_, i, j)].occ_state == -1) {
1278 AmclNode::Point2D point = {i, j};
1279 free_space_indices.push_back(point);
1286 AmclNode::freeMapDependentMemory()
1296 lasers_update_.clear();
1297 frame_to_laser_.clear();
1303 AmclNode::convertMap(
const nav_msgs::msg::OccupancyGrid & map_msg)
1305 map_t * map = map_alloc();
1307 map->size_x = map_msg.info.width;
1308 map->size_y = map_msg.info.height;
1309 map->scale = map_msg.info.resolution;
1310 map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
1311 map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
1317 for (
int i = 0; i < map->size_x * map->size_y; i++) {
1318 if (map_msg.data[i] == 0) {
1319 map->cells[i].occ_state = -1;
1320 }
else if (map_msg.data[i] == 100) {
1321 map->cells[i].occ_state = +1;
1323 map->cells[i].occ_state = 0;
1331 AmclNode::initTransforms()
1333 RCLCPP_INFO(get_logger(),
"initTransforms");
1336 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
1337 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
1338 get_node_base_interface(),
1339 get_node_timers_interface(),
1341 tf_buffer_->setCreateTimerInterface(timer_interface);
1342 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_,
this,
true);
1343 tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
1345 sent_first_transform_ =
false;
1346 latest_tf_valid_ =
false;
1347 latest_tf_ = tf2::Transform::getIdentity();
1351 AmclNode::initMessageFilters()
1353 auto sub_opt = rclcpp::SubscriptionOptions();
1354 sub_opt.callback_group = callback_group_;
1356 #if RCLCPP_VERSION_GTE(29, 6, 0)
1357 laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
1360 laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
1361 rclcpp_lifecycle::LifecycleNode>>(
1362 std::static_pointer_cast<rclcpp_lifecycle::LifecycleNode>(shared_from_this()),
1366 laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
1367 *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
1368 get_node_logging_interface(),
1369 get_node_clock_interface(),
1370 transform_tolerance_);
1373 laser_scan_connection_ = laser_scan_filter_->registerCallback(
1374 std::bind(&AmclNode::laserReceived,
this, std::placeholders::_1));
1378 AmclNode::initPubSub()
1380 RCLCPP_INFO(get_logger(),
"initPubSub");
1382 particle_cloud_pub_ = create_publisher<nav2_msgs::msg::ParticleCloud>(
1386 pose_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
1390 initial_pose_sub_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
1392 std::bind(&AmclNode::initialPoseReceived,
this, std::placeholders::_1));
1394 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1396 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1),
1399 RCLCPP_INFO(get_logger(),
"Subscribed to map topic.");
1403 AmclNode::initServices()
1405 global_loc_srv_ = create_service<std_srvs::srv::Empty>(
1406 "reinitialize_global_localization",
1407 std::bind(&AmclNode::globalLocalizationCallback,
this, std::placeholders::_1,
1408 std::placeholders::_2, std::placeholders::_3));
1410 initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
1412 std::bind(&AmclNode::initialPoseReceivedSrv,
this, std::placeholders::_1, std::placeholders::_2,
1413 std::placeholders::_3));
1415 nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
1416 "request_nomotion_update",
1417 std::bind(&AmclNode::nomotionUpdateCallback,
this, std::placeholders::_1, std::placeholders::_2,
1418 std::placeholders::_3));
1422 AmclNode::initOdometry()
1428 init_pose_[0] = last_published_pose_.pose.pose.position.x;
1429 init_pose_[1] = last_published_pose_.pose.pose.position.y;
1430 init_pose_[2] = tf2::getYaw(last_published_pose_.pose.pose.orientation);
1432 if (!initial_pose_is_known_) {
1433 init_cov_[0] = 0.5 * 0.5;
1434 init_cov_[1] = 0.5 * 0.5;
1435 init_cov_[2] = (M_PI / 12.0) * (M_PI / 12.0);
1437 init_cov_[0] = last_published_pose_.pose.covariance[0];
1438 init_cov_[1] = last_published_pose_.pose.covariance[7];
1439 init_cov_[2] = last_published_pose_.pose.covariance[35];
1442 motion_model_ = plugin_loader_.createSharedInstance(robot_model_type_);
1443 motion_model_->initialize(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
1445 latest_odom_pose_ = geometry_msgs::msg::PoseStamped();
1449 AmclNode::initParticleFilter()
1453 min_particles_, max_particles_, alpha_slow_, alpha_fast_,
1454 (pf_init_model_fn_t)AmclNode::uniformPoseGenerator);
1455 pf_->pop_err = pf_err_;
1460 pf_init_pose_mean.v[0] = init_pose_[0];
1461 pf_init_pose_mean.v[1] = init_pose_[1];
1462 pf_init_pose_mean.v[2] = init_pose_[2];
1465 pf_init_pose_cov.m[0][0] = init_cov_[0];
1466 pf_init_pose_cov.m[1][1] = init_cov_[1];
1467 pf_init_pose_cov.m[2][2] = init_cov_[2];
1469 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
1472 resample_count_ = 0;
1473 memset(&pf_odom_pose_, 0,
sizeof(pf_odom_pose_));
1477 AmclNode::initLaserScan()
1479 scan_error_count_ = 0;
1480 last_laser_received_ts_ = rclcpp::Time(0);
1485 #include "rclcpp_components/register_node_macro.hpp"
A QoS profile for latched, reliable topics with a history of 1 messages.
A QoS profile for latched, reliable topics with a history of 10 messages.
A QoS profile for best-effort sensor data with a history of 10 messages.