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 post_set_params_handler_ = node->add_post_set_parameters_callback(
121 &AmclNode::updateParametersCallback,
122 this, std::placeholders::_1));
123 on_set_params_handler_ = node->add_on_set_parameters_callback(
125 &AmclNode::validateParameterUpdatesCallback,
126 this, std::placeholders::_1));
131 return nav2::CallbackReturn::SUCCESS;
135 AmclNode::on_deactivate(
const rclcpp_lifecycle::State & )
137 RCLCPP_INFO(get_logger(),
"Deactivating");
142 pose_pub_->on_deactivate();
143 particle_cloud_pub_->on_deactivate();
146 remove_post_set_parameters_callback(post_set_params_handler_.get());
147 post_set_params_handler_.reset();
148 remove_on_set_parameters_callback(on_set_params_handler_.get());
149 on_set_params_handler_.reset();
154 return nav2::CallbackReturn::SUCCESS;
158 AmclNode::on_cleanup(
const rclcpp_lifecycle::State & )
160 RCLCPP_INFO(get_logger(),
"Cleaning up");
162 executor_thread_.reset();
166 global_loc_srv_.reset();
167 initial_guess_srv_.reset();
168 nomotion_update_srv_.reset();
169 initial_pose_sub_.reset();
170 laser_scan_connection_.disconnect();
171 tf_listener_.reset();
172 laser_scan_filter_.reset();
173 laser_scan_sub_.reset();
181 first_map_received_ =
false;
182 free_space_indices.resize(0);
185 tf_broadcaster_.reset();
190 particle_cloud_pub_.reset();
193 motion_model_.reset();
201 lasers_update_.clear();
202 frame_to_laser_.clear();
203 force_update_ =
true;
205 if (set_initial_pose_) {
209 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.x)));
213 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.y)));
217 rclcpp::ParameterValue(last_published_pose_.pose.pose.position.z)));
221 rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation))));
224 return nav2::CallbackReturn::SUCCESS;
228 AmclNode::on_shutdown(
const rclcpp_lifecycle::State & )
230 RCLCPP_INFO(get_logger(),
"Shutting down");
231 return nav2::CallbackReturn::SUCCESS;
235 AmclNode::checkElapsedTime(std::chrono::seconds check_interval, rclcpp::Time last_time)
237 rclcpp::Duration elapsed_time = now() - last_time;
238 if (elapsed_time.nanoseconds() * 1e-9 > check_interval.count()) {
244 #if NEW_UNIFORM_SAMPLING
245 std::vector<AmclNode::Point2D> AmclNode::free_space_indices;
249 AmclNode::getOdomPose(
250 geometry_msgs::msg::PoseStamped & odom_pose,
251 double & x,
double & y,
double & yaw,
252 const rclcpp::Time & sensor_timestamp,
const std::string & frame_id)
255 geometry_msgs::msg::PoseStamped ident;
256 ident.header.frame_id = frame_id;
257 ident.header.stamp = sensor_timestamp;
258 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
261 tf_buffer_->transform(ident, odom_pose, odom_frame_id_);
262 }
catch (tf2::TransformException & e) {
264 if (scan_error_count_ % 20 == 0) {
266 get_logger(),
"(%d) consecutive laser scan transforms failed: (%s)", scan_error_count_,
272 scan_error_count_ = 0;
273 x = odom_pose.pose.position.x;
274 y = odom_pose.pose.position.y;
275 yaw = tf2::getYaw(odom_pose.pose.orientation);
281 AmclNode::uniformPoseGenerator(
void * arg)
285 #if NEW_UNIFORM_SAMPLING
286 unsigned int rand_index = drand48() * free_space_indices.size();
287 AmclNode::Point2D free_point = free_space_indices[rand_index];
289 p.v[0] = MAP_WXGX(map, free_point.x);
290 p.v[1] = MAP_WYGY(map, free_point.y);
291 p.v[2] = drand48() * 2 * M_PI - M_PI;
293 double min_x, max_x, min_y, max_y;
295 min_x = (map->size_x * map->scale) / 2.0 - map->origin_x;
296 max_x = (map->size_x * map->scale) / 2.0 + map->origin_x;
297 min_y = (map->size_y * map->scale) / 2.0 - map->origin_y;
298 max_y = (map->size_y * map->scale) / 2.0 + map->origin_y;
302 RCLCPP_DEBUG(get_logger(),
"Generating new uniform sample");
304 p.v[0] = min_x + drand48() * (max_x - min_x);
305 p.v[1] = min_y + drand48() * (max_y - min_y);
306 p.v[2] = drand48() * 2 * M_PI - M_PI;
309 i = MAP_GXWX(map, p.v[0]);
310 j = MAP_GYWY(map, p.v[1]);
311 if (MAP_VALID(map, i, j) && (map->cells[MAP_INDEX(map, i, j)].occ_state == -1)) {
320 AmclNode::globalLocalizationCallback(
321 const std::shared_ptr<rmw_request_id_t>,
322 const std::shared_ptr<std_srvs::srv::Empty::Request>,
323 std::shared_ptr<std_srvs::srv::Empty::Response>)
325 std::lock_guard<std::recursive_mutex> cfl(mutex_);
327 RCLCPP_INFO(get_logger(),
"Initializing with uniform distribution");
330 pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
331 reinterpret_cast<void *
>(map_));
332 RCLCPP_INFO(get_logger(),
"Global initialisation done!");
333 initial_pose_is_known_ =
true;
338 AmclNode::initialPoseReceivedSrv(
339 const std::shared_ptr<rmw_request_id_t>,
340 const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
341 std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>)
343 initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
348 AmclNode::nomotionUpdateCallback(
349 const std::shared_ptr<rmw_request_id_t>,
350 const std::shared_ptr<std_srvs::srv::Empty::Request>,
351 std::shared_ptr<std_srvs::srv::Empty::Response>)
353 RCLCPP_INFO(get_logger(),
"Requesting no-motion update");
354 force_update_ =
true;
358 AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
360 std::lock_guard<std::recursive_mutex> cfl(mutex_);
362 RCLCPP_INFO(get_logger(),
"initialPoseReceived");
364 if (!nav2::validateMsg(*msg)) {
365 RCLCPP_ERROR(get_logger(),
"Received initialpose message is malformed. Rejecting.");
368 if (msg->header.frame_id != global_frame_id_) {
371 "Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"",
372 msg->header.frame_id.c_str(),
373 global_frame_id_.c_str());
376 if (first_map_received_ && (abs(msg->pose.pose.position.x) > map_->size_x ||
377 abs(msg->pose.pose.position.y) > map_->size_y))
380 get_logger(),
"Received initialpose from message is out of the size of map. Rejecting.");
385 last_published_pose_ = *msg;
388 init_pose_received_on_inactive =
true;
390 get_logger(),
"Received initial pose request, "
391 "but AMCL is not yet in the active state");
394 handleInitialPose(*msg);
398 AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
400 std::lock_guard<std::recursive_mutex> cfl(mutex_);
403 geometry_msgs::msg::TransformStamped tx_odom;
405 rclcpp::Time rclcpp_time = now();
406 tf2::TimePoint tf2_time(std::chrono::nanoseconds(rclcpp_time.nanoseconds()));
409 tx_odom = tf_buffer_->lookupTransform(
410 base_frame_id_, tf2_ros::fromMsg(msg.header.stamp),
411 base_frame_id_, tf2_time, odom_frame_id_);
412 }
catch (tf2::TransformException & e) {
417 if (sent_first_transform_) {
418 RCLCPP_WARN(get_logger(),
"Failed to transform initial pose in time (%s)", e.what());
420 tf2::impl::Converter<false, true>::convert(tf2::Transform::getIdentity(), tx_odom.transform);
423 tf2::Transform tx_odom_tf2;
424 tf2::impl::Converter<true, false>::convert(tx_odom.transform, tx_odom_tf2);
426 tf2::Transform pose_old;
427 tf2::impl::Converter<true, false>::convert(msg.pose.pose, pose_old);
429 tf2::Transform pose_new = pose_old * tx_odom_tf2;
434 get_logger(),
"Setting pose (%.6f): %.3f %.3f %.3f",
435 now().nanoseconds() * 1e-9,
436 pose_new.getOrigin().x(),
437 pose_new.getOrigin().y(),
438 tf2::getYaw(pose_new.getRotation()));
442 pf_init_pose_mean.v[0] = pose_new.getOrigin().x();
443 pf_init_pose_mean.v[1] = pose_new.getOrigin().y();
444 pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation());
448 for (
int i = 0; i < 2; i++) {
449 for (
int j = 0; j < 2; j++) {
450 pf_init_pose_cov.m[i][j] = msg.pose.covariance[6 * i + j];
454 pf_init_pose_cov.m[2][2] = msg.pose.covariance[6 * 5 + 5];
456 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
458 init_pose_received_on_inactive =
false;
459 initial_pose_is_known_ =
true;
463 AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
465 std::lock_guard<std::recursive_mutex> cfl(mutex_);
469 if (!active_) {
return;}
470 if (!first_map_received_) {
471 if (checkElapsedTime(2s, last_time_printed_msg_)) {
472 RCLCPP_WARN(get_logger(),
"Waiting for map....");
473 last_time_printed_msg_ = now();
478 std::string laser_scan_frame_id = laser_scan->header.frame_id;
479 last_laser_received_ts_ = now();
480 int laser_index = -1;
481 geometry_msgs::msg::PoseStamped laser_pose;
484 if (frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) {
485 if (!addNewScanner(laser_index, laser_scan, laser_scan_frame_id, laser_pose)) {
490 laser_index = frame_to_laser_[laser_scan->header.frame_id];
496 latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
497 laser_scan->header.stamp, base_frame_id_))
499 RCLCPP_ERROR(get_logger(),
"Couldn't determine robot's pose associated with laser scan");
504 bool force_publication =
false;
507 pf_odom_pose_ = pose;
510 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
511 lasers_update_[i] =
true;
514 force_publication =
true;
518 if (shouldUpdateFilter(pose, delta)) {
519 for (
unsigned int i = 0; i < lasers_update_.size(); i++) {
520 lasers_update_[i] =
true;
523 if (lasers_update_[laser_index]) {
524 motion_model_->odometryUpdate(pf_, pose, delta);
526 force_update_ =
false;
529 bool resampled =
false;
532 if (lasers_update_[laser_index]) {
533 updateFilter(laser_index, laser_scan, pose);
536 if (!(++resample_count_ % resample_interval_)) {
537 pf_update_resample(pf_,
reinterpret_cast<void *
>(map_));
542 RCLCPP_DEBUG(get_logger(),
"Num samples: %d\n", set->sample_count);
544 if (!force_update_) {
545 publishParticleCloud(set);
548 if (resampled || force_publication || !first_pose_sent_) {
549 amcl_hyp_t max_weight_hyps;
550 std::vector<amcl_hyp_t> hyps;
551 int max_weight_hyp = -1;
552 if (getMaxWeightHyp(hyps, max_weight_hyps, max_weight_hyp)) {
553 publishAmclPose(laser_scan, hyps, max_weight_hyp);
554 calculateMaptoOdomTransform(laser_scan, hyps, max_weight_hyp);
556 if (tf_broadcast_ ==
true) {
559 auto stamp = tf2_ros::fromMsg(laser_scan->header.stamp);
560 tf2::TimePoint transform_expiration = stamp + transform_tolerance_;
561 sendMapToOdomTransform(transform_expiration);
562 sent_first_transform_ =
true;
565 RCLCPP_ERROR(get_logger(),
"No pose!");
567 }
else if (latest_tf_valid_) {
568 if (tf_broadcast_ ==
true) {
571 tf2::TimePoint transform_expiration = tf2_ros::fromMsg(laser_scan->header.stamp) +
572 transform_tolerance_;
573 sendMapToOdomTransform(transform_expiration);
578 bool AmclNode::addNewScanner(
580 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
581 const std::string & laser_scan_frame_id,
582 geometry_msgs::msg::PoseStamped & laser_pose)
584 lasers_.push_back(createLaserObject());
585 lasers_update_.push_back(
true);
586 laser_index = frame_to_laser_.size();
588 geometry_msgs::msg::PoseStamped ident;
589 ident.header.frame_id = laser_scan_frame_id;
590 ident.header.stamp = rclcpp::Time();
591 tf2::toMsg(tf2::Transform::getIdentity(), ident.pose);
593 tf_buffer_->transform(ident, laser_pose, base_frame_id_, transform_tolerance_);
594 }
catch (tf2::TransformException & e) {
596 get_logger(),
"Couldn't transform from %s to %s, "
597 "even though the message notifier is in use: (%s)",
598 laser_scan->header.frame_id.c_str(),
599 base_frame_id_.c_str(), e.what());
604 laser_pose_v.v[0] = laser_pose.pose.position.x;
605 laser_pose_v.v[1] = laser_pose.pose.position.y;
607 laser_pose_v.v[2] = 0;
608 lasers_[laser_index]->SetLaserPose(laser_pose_v);
609 frame_to_laser_[laser_scan->header.frame_id] = laser_index;
615 delta.v[0] = pose.v[0] - pf_odom_pose_.v[0];
616 delta.v[1] = pose.v[1] - pf_odom_pose_.v[1];
617 delta.v[2] = angleutils::angle_diff(pose.v[2], pf_odom_pose_.v[2]);
620 bool update = fabs(delta.v[0]) > d_thresh_ ||
621 fabs(delta.v[1]) > d_thresh_ ||
622 fabs(delta.v[2]) > a_thresh_;
623 update = update || force_update_;
627 bool AmclNode::updateFilter(
628 const int & laser_index,
629 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
633 ldata.laser = lasers_[laser_index];
634 ldata.range_count = laser_scan->ranges.size();
640 geometry_msgs::msg::QuaternionStamped min_q, inc_q;
641 min_q.header.stamp = laser_scan->header.stamp;
642 min_q.header.frame_id = laser_scan->header.frame_id;
643 min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min);
645 inc_q.header = min_q.header;
646 inc_q.quaternion = orientationAroundZAxis(laser_scan->angle_min + laser_scan->angle_increment);
648 tf_buffer_->transform(min_q, min_q, base_frame_id_);
649 tf_buffer_->transform(inc_q, inc_q, base_frame_id_);
650 }
catch (tf2::TransformException & e) {
652 get_logger(),
"Unable to transform min/max laser angles into base frame: %s",
656 double angle_min = tf2::getYaw(min_q.quaternion);
657 double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min;
660 angle_increment = fmod(angle_increment + 5 * M_PI, 2 * M_PI) - M_PI;
663 get_logger(),
"Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min,
667 if (laser_scan->range_max <= 0.0) {
669 get_logger(),
"wrong range_max of laser_scan data: %f. The message could be malformed."
670 " Ignore this message and stop updating.",
671 laser_scan->range_max);
676 if (laser_max_range_ > 0.0) {
677 ldata.range_max = std::min(laser_scan->range_max,
static_cast<float>(laser_max_range_));
679 ldata.range_max = laser_scan->range_max;
682 if (laser_min_range_ > 0.0) {
683 range_min = std::max(laser_scan->range_min,
static_cast<float>(laser_min_range_));
685 range_min = laser_scan->range_min;
689 ldata.ranges =
new double[ldata.range_count][2];
690 for (
int i = 0; i < ldata.range_count; i++) {
693 if (laser_scan->ranges[i] <= range_min) {
694 ldata.ranges[i][0] = ldata.range_max;
696 ldata.ranges[i][0] = laser_scan->ranges[i];
699 ldata.ranges[i][1] = angle_min +
700 (i * angle_increment);
703 lasers_update_[laser_index] =
false;
704 pf_odom_pose_ = pose;
712 if (!initial_pose_is_known_) {
return;}
713 auto cloud_with_weights_msg = std::make_unique<nav2_msgs::msg::ParticleCloud>();
714 cloud_with_weights_msg->header.stamp = this->now();
715 cloud_with_weights_msg->header.frame_id = global_frame_id_;
716 cloud_with_weights_msg->particles.resize(set->sample_count);
718 for (
int i = 0; i < set->sample_count; i++) {
719 cloud_with_weights_msg->particles[i].pose.position.x = set->samples[i].pose.v[0];
720 cloud_with_weights_msg->particles[i].pose.position.y = set->samples[i].pose.v[1];
721 cloud_with_weights_msg->particles[i].pose.position.z = 0;
722 cloud_with_weights_msg->particles[i].pose.orientation = orientationAroundZAxis(
723 set->samples[i].pose.v[2]);
724 cloud_with_weights_msg->particles[i].weight = set->samples[i].weight;
727 particle_cloud_pub_->publish(std::move(cloud_with_weights_msg));
731 AmclNode::getMaxWeightHyp(
732 std::vector<amcl_hyp_t> & hyps, amcl_hyp_t & max_weight_hyps,
733 int & max_weight_hyp)
736 double max_weight = 0.0;
737 hyps.resize(pf_->sets[pf_->current_set].cluster_count);
738 for (
int hyp_count = 0;
739 hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++)
744 if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) {
745 RCLCPP_ERROR(get_logger(),
"Couldn't get stats on cluster %d", hyp_count);
749 hyps[hyp_count].weight = weight;
750 hyps[hyp_count].pf_pose_mean = pose_mean;
751 hyps[hyp_count].pf_pose_cov = pose_cov;
753 if (hyps[hyp_count].weight > max_weight) {
754 max_weight = hyps[hyp_count].weight;
755 max_weight_hyp = hyp_count;
759 if (max_weight > 0.0) {
761 get_logger(),
"Max weight pose: %.3f %.3f %.3f",
762 hyps[max_weight_hyp].pf_pose_mean.v[0],
763 hyps[max_weight_hyp].pf_pose_mean.v[1],
764 hyps[max_weight_hyp].pf_pose_mean.v[2]);
766 max_weight_hyps = hyps[max_weight_hyp];
773 AmclNode::publishAmclPose(
774 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
775 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
778 if (!initial_pose_is_known_) {
779 if (checkElapsedTime(2s, last_time_printed_msg_)) {
781 get_logger(),
"AMCL cannot publish a pose or update the transform. "
782 "Please set the initial pose...");
783 last_time_printed_msg_ = now();
788 auto p = std::make_unique<geometry_msgs::msg::PoseWithCovarianceStamped>();
790 p->header.frame_id = global_frame_id_;
791 p->header.stamp = laser_scan->header.stamp;
793 p->pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
794 p->pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
795 p->pose.pose.orientation = orientationAroundZAxis(hyps[max_weight_hyp].pf_pose_mean.v[2]);
798 for (
int i = 0; i < 2; i++) {
799 for (
int j = 0; j < 2; j++) {
803 p->pose.covariance[6 * i + j] = set->cov.m[i][j];
806 p->pose.covariance[6 * 5 + 5] = set->cov.m[2][2];
808 for (
auto covariance_value : p->pose.covariance) {
809 temp += covariance_value;
811 temp += p->pose.pose.position.x + p->pose.pose.position.y;
812 if (!std::isnan(temp)) {
813 RCLCPP_DEBUG(get_logger(),
"Publishing pose");
814 last_published_pose_ = *p;
815 first_pose_sent_ =
true;
816 pose_pub_->publish(std::move(p));
819 get_logger(),
"AMCL covariance or pose is NaN, likely due to an invalid "
820 "configuration or faulty sensor measurements! Pose is not available!");
824 get_logger(),
"New pose: %6.3f %6.3f %6.3f",
825 hyps[max_weight_hyp].pf_pose_mean.v[0],
826 hyps[max_weight_hyp].pf_pose_mean.v[1],
827 hyps[max_weight_hyp].pf_pose_mean.v[2]);
831 AmclNode::calculateMaptoOdomTransform(
832 const sensor_msgs::msg::LaserScan::ConstSharedPtr & laser_scan,
833 const std::vector<amcl_hyp_t> & hyps,
const int & max_weight_hyp)
836 geometry_msgs::msg::PoseStamped odom_to_map;
839 q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]);
840 tf2::Transform tmp_tf(q, tf2::Vector3(
841 hyps[max_weight_hyp].pf_pose_mean.v[0],
842 hyps[max_weight_hyp].pf_pose_mean.v[1],
845 geometry_msgs::msg::PoseStamped tmp_tf_stamped;
846 tmp_tf_stamped.header.frame_id = base_frame_id_;
847 tmp_tf_stamped.header.stamp = laser_scan->header.stamp;
848 tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose);
850 tf_buffer_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_);
851 }
catch (tf2::TransformException & e) {
852 RCLCPP_DEBUG(get_logger(),
"Failed to subtract base to odom transform: (%s)", e.what());
856 tf2::impl::Converter<true, false>::convert(odom_to_map.pose, latest_tf_);
857 latest_tf_valid_ =
true;
861 AmclNode::sendMapToOdomTransform(
const tf2::TimePoint & transform_expiration)
864 if (!initial_pose_is_known_) {
return;}
865 geometry_msgs::msg::TransformStamped tmp_tf_stamped;
866 tmp_tf_stamped.header.frame_id = global_frame_id_;
867 tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_expiration);
868 tmp_tf_stamped.child_frame_id = odom_frame_id_;
869 tf2::impl::Converter<false, true>::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);
870 tf_broadcaster_->sendTransform(tmp_tf_stamped);
874 AmclNode::createLaserObject()
876 RCLCPP_INFO(get_logger(),
"createLaserObject");
878 if (sensor_model_type_ ==
"beam") {
880 z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_,
881 0.0, max_beams_, map_);
884 if (sensor_model_type_ ==
"likelihood_field_prob") {
886 z_hit_, z_rand_, sigma_hit_,
887 laser_likelihood_max_dist_, do_beamskip_, beam_skip_distance_, beam_skip_threshold_,
888 beam_skip_error_threshold_, max_beams_, map_);
892 z_hit_, z_rand_, sigma_hit_,
893 laser_likelihood_max_dist_, max_beams_, map_);
897 AmclNode::initParameters()
899 double save_pose_rate;
902 alpha1_ = this->declare_or_get_parameter(
"alpha1", 0.2);
903 alpha2_ = this->declare_or_get_parameter(
"alpha2", 0.2);
904 alpha3_ = this->declare_or_get_parameter(
"alpha3", 0.2);
905 alpha4_ = this->declare_or_get_parameter(
"alpha4", 0.2);
906 alpha5_ = this->declare_or_get_parameter(
"alpha5", 0.2);
907 base_frame_id_ = this->declare_or_get_parameter(
"base_frame_id", std::string{
"base_footprint"});
908 beam_skip_distance_ = this->declare_or_get_parameter(
"beam_skip_distance", 0.5);
909 beam_skip_error_threshold_ = this->declare_or_get_parameter(
"beam_skip_error_threshold", 0.9);
910 beam_skip_threshold_ = this->declare_or_get_parameter(
"beam_skip_threshold", 0.3);
911 do_beamskip_ = this->declare_or_get_parameter(
"do_beamskip",
false);
912 global_frame_id_ = this->declare_or_get_parameter(
"global_frame_id", std::string{
"map"});
913 lambda_short_ = this->declare_or_get_parameter(
"lambda_short", 0.1);
914 laser_likelihood_max_dist_ = this->declare_or_get_parameter(
"laser_likelihood_max_dist", 2.0);
915 laser_max_range_ = this->declare_or_get_parameter(
"laser_max_range", 100.0);
916 laser_min_range_ = this->declare_or_get_parameter(
"laser_min_range", -1.0);
917 sensor_model_type_ = this->declare_or_get_parameter(
918 "laser_model_type", std::string{
"likelihood_field"});
919 set_initial_pose_ = this->declare_or_get_parameter(
"set_initial_pose",
false);
920 initial_pose_x_ = this->declare_or_get_parameter(
"initial_pose.x", 0.0);
921 initial_pose_y_ = this->declare_or_get_parameter(
"initial_pose.y", 0.0);
922 initial_pose_z_ = this->declare_or_get_parameter(
"initial_pose.z", 0.0);
923 initial_pose_yaw_ = this->declare_or_get_parameter(
"initial_pose.yaw", 0.0);
924 max_beams_ = this->declare_or_get_parameter(
"max_beams", 60);
925 max_particles_ = this->declare_or_get_parameter(
"max_particles", 2000);
926 min_particles_ = this->declare_or_get_parameter(
"min_particles", 500);
927 odom_frame_id_ = this->declare_or_get_parameter(
"odom_frame_id", std::string{
"odom"});
928 pf_err_ = this->declare_or_get_parameter(
"pf_err", 0.05);
929 pf_z_ = this->declare_or_get_parameter(
"pf_z", 0.99);
930 alpha_fast_ = this->declare_or_get_parameter(
"recovery_alpha_fast", 0.0);
931 alpha_slow_ = this->declare_or_get_parameter(
"recovery_alpha_slow", 0.0);
932 resample_interval_ = this->declare_or_get_parameter(
"resample_interval", 1);
933 robot_model_type_ = this->declare_or_get_parameter(
934 "robot_model_type", std::string{
"nav2_amcl::DifferentialMotionModel"});
935 save_pose_rate = this->declare_or_get_parameter(
"save_pose_rate", 0.5);
936 sigma_hit_ = this->declare_or_get_parameter(
"sigma_hit", 0.2);
937 tf_broadcast_ = this->declare_or_get_parameter(
"tf_broadcast",
true);
938 tmp_tol = this->declare_or_get_parameter(
"transform_tolerance", 1.0);
939 a_thresh_ = this->declare_or_get_parameter(
"update_min_a", 0.2);
940 d_thresh_ = this->declare_or_get_parameter(
"update_min_d", 0.25);
941 z_hit_ = this->declare_or_get_parameter(
"z_hit", 0.5);
942 z_max_ = this->declare_or_get_parameter(
"z_max", 0.05);
943 z_rand_ = this->declare_or_get_parameter(
"z_rand", 0.5);
944 z_short_ = this->declare_or_get_parameter(
"z_short", 0.05);
945 first_map_only_ = this->declare_or_get_parameter(
"first_map_only",
false);
946 always_reset_initial_pose_ = this->declare_or_get_parameter(
"always_reset_initial_pose",
false);
947 scan_topic_ = this->declare_or_get_parameter(
"scan_topic", std::string{
"scan"});
948 map_topic_ = this->declare_or_get_parameter(
"map_topic", std::string{
"map"});
949 freespace_downsampling_ = this->declare_or_get_parameter(
"freespace_downsampling",
false);
951 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
952 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
953 last_time_printed_msg_ = now();
956 if (laser_likelihood_max_dist_ < 0) {
958 get_logger(),
"You've set laser_likelihood_max_dist to be negative,"
959 " this isn't allowed so it will be set to default value 2.0.");
960 laser_likelihood_max_dist_ = 2.0;
962 if (max_particles_ < 0) {
964 get_logger(),
"You've set max_particles to be negative,"
965 " this isn't allowed so it will be set to default value 2000.");
966 max_particles_ = 2000;
969 if (min_particles_ < 0) {
971 get_logger(),
"You've set min_particles to be negative,"
972 " this isn't allowed so it will be set to default value 500.");
973 min_particles_ = 500;
976 if (min_particles_ > max_particles_) {
978 get_logger(),
"You've set min_particles to be greater than max particles,"
979 " this isn't allowed so max_particles will be set to min_particles.");
980 max_particles_ = min_particles_;
983 if (resample_interval_ <= 0) {
985 get_logger(),
"You've set resample_interval to be zero or negative,"
986 " this isn't allowed so it will be set to default value to 1.");
987 resample_interval_ = 1;
990 if (always_reset_initial_pose_) {
991 initial_pose_is_known_ =
false;
995 rcl_interfaces::msg::SetParametersResult AmclNode::validateParameterUpdatesCallback(
996 std::vector<rclcpp::Parameter> parameters)
998 rcl_interfaces::msg::SetParametersResult result;
999 result.successful =
true;
1000 for (
auto parameter : parameters) {
1001 const auto & param_type = parameter.get_type();
1002 const auto & param_name = parameter.get_name();
1003 if (param_name.find(
'.') != std::string::npos) {
1006 if (param_type == ParameterType::PARAMETER_DOUBLE) {
1007 if (parameter.as_double() < 0.0 &&
1008 (param_name !=
"laser_min_range" || param_name !=
"laser_max_range"))
1011 get_logger(),
"The value of parameter '%s' is incorrectly set to %f, "
1012 "it should be >=0. Ignoring parameter update.",
1013 param_name.c_str(), parameter.as_double());
1014 result.successful =
false;
1016 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
1017 if (parameter.as_int() <= 0.0 && param_name ==
"resample_interval") {
1019 get_logger(),
"The value of resample_interval is incorrectly set, "
1020 "it should be >0. Ignoring parameter update.");
1021 result.successful =
false;
1022 }
else if (parameter.as_int() < 0.0) {
1024 get_logger(),
"The value of parameter '%s' is incorrectly set to %ld, "
1025 "it should be >=0. Ignoring parameter update.",
1026 param_name.c_str(), parameter.as_int());
1027 result.successful =
false;
1028 }
else if (param_name ==
"max_particles" && parameter.as_int() < min_particles_) {
1030 get_logger(),
"The value of max_particles is incorrectly set, "
1031 "it should be larger than min_particles. Ignoring parameter update.");
1032 result.successful =
false;
1033 }
else if (param_name ==
"min_particles" && parameter.as_int() > max_particles_) {
1035 get_logger(),
"The value of min_particles is incorrectly set, "
1036 "it should be smaller than max particles. Ignoring parameter update.");
1037 result.successful =
false;
1045 AmclNode::updateParametersCallback(
1046 std::vector<rclcpp::Parameter> parameters)
1048 std::lock_guard<std::recursive_mutex> cfl(mutex_);
1050 bool reinit_pf =
false;
1051 bool reinit_odom =
false;
1052 bool reinit_laser =
false;
1053 bool reinit_map =
false;
1055 for (
const auto & parameter : parameters) {
1056 const auto & param_type = parameter.get_type();
1057 const auto & param_name = parameter.get_name();
1058 if (param_name.find(
'.') != std::string::npos) {
1061 if (param_type == ParameterType::PARAMETER_DOUBLE) {
1062 if (param_name ==
"alpha1") {
1063 alpha1_ = parameter.as_double();
1065 }
else if (param_name ==
"alpha2") {
1066 alpha2_ = parameter.as_double();
1068 }
else if (param_name ==
"alpha3") {
1069 alpha3_ = parameter.as_double();
1071 }
else if (param_name ==
"alpha4") {
1072 alpha4_ = parameter.as_double();
1074 }
else if (param_name ==
"alpha5") {
1075 alpha5_ = parameter.as_double();
1077 }
else if (param_name ==
"beam_skip_distance") {
1078 beam_skip_distance_ = parameter.as_double();
1079 reinit_laser =
true;
1080 }
else if (param_name ==
"beam_skip_error_threshold") {
1081 beam_skip_error_threshold_ = parameter.as_double();
1082 reinit_laser =
true;
1083 }
else if (param_name ==
"beam_skip_threshold") {
1084 beam_skip_threshold_ = parameter.as_double();
1085 reinit_laser =
true;
1086 }
else if (param_name ==
"lambda_short") {
1087 lambda_short_ = parameter.as_double();
1088 reinit_laser =
true;
1089 }
else if (param_name ==
"laser_likelihood_max_dist") {
1090 laser_likelihood_max_dist_ = parameter.as_double();
1091 reinit_laser =
true;
1092 }
else if (param_name ==
"laser_max_range") {
1093 laser_max_range_ = parameter.as_double();
1094 reinit_laser =
true;
1095 }
else if (param_name ==
"laser_min_range") {
1096 laser_min_range_ = parameter.as_double();
1097 reinit_laser =
true;
1098 }
else if (param_name ==
"pf_err") {
1099 pf_err_ = parameter.as_double();
1101 }
else if (param_name ==
"pf_z") {
1102 pf_z_ = parameter.as_double();
1104 }
else if (param_name ==
"recovery_alpha_fast") {
1105 alpha_fast_ = parameter.as_double();
1107 }
else if (param_name ==
"recovery_alpha_slow") {
1108 alpha_slow_ = parameter.as_double();
1110 }
else if (param_name ==
"save_pose_rate") {
1111 double save_pose_rate = parameter.as_double();
1112 save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
1113 }
else if (param_name ==
"sigma_hit") {
1114 sigma_hit_ = parameter.as_double();
1115 reinit_laser =
true;
1116 }
else if (param_name ==
"transform_tolerance") {
1117 double tmp_tol = parameter.as_double();
1118 transform_tolerance_ = tf2::durationFromSec(tmp_tol);
1119 reinit_laser =
true;
1120 }
else if (param_name ==
"update_min_a") {
1121 a_thresh_ = parameter.as_double();
1122 }
else if (param_name ==
"update_min_d") {
1123 d_thresh_ = parameter.as_double();
1124 }
else if (param_name ==
"z_hit") {
1125 z_hit_ = parameter.as_double();
1126 reinit_laser =
true;
1127 }
else if (param_name ==
"z_max") {
1128 z_max_ = parameter.as_double();
1129 reinit_laser =
true;
1130 }
else if (param_name ==
"z_rand") {
1131 z_rand_ = parameter.as_double();
1132 reinit_laser =
true;
1133 }
else if (param_name ==
"z_short") {
1134 z_short_ = parameter.as_double();
1135 reinit_laser =
true;
1137 }
else if (param_type == ParameterType::PARAMETER_STRING) {
1138 if (param_name ==
"base_frame_id") {
1139 base_frame_id_ = parameter.as_string();
1140 }
else if (param_name ==
"global_frame_id") {
1141 global_frame_id_ = parameter.as_string();
1142 }
else if (param_name ==
"map_topic") {
1143 map_topic_ = parameter.as_string();
1145 }
else if (param_name ==
"laser_model_type") {
1146 sensor_model_type_ = parameter.as_string();
1147 reinit_laser =
true;
1148 }
else if (param_name ==
"odom_frame_id") {
1149 odom_frame_id_ = parameter.as_string();
1150 reinit_laser =
true;
1151 }
else if (param_name ==
"scan_topic") {
1152 scan_topic_ = parameter.as_string();
1153 reinit_laser =
true;
1154 }
else if (param_name ==
"robot_model_type") {
1155 robot_model_type_ = parameter.as_string();
1158 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
1159 if (param_name ==
"do_beamskip") {
1160 do_beamskip_ = parameter.as_bool();
1161 reinit_laser =
true;
1162 }
else if (param_name ==
"tf_broadcast") {
1163 tf_broadcast_ = parameter.as_bool();
1164 }
else if (param_name ==
"set_initial_pose") {
1165 set_initial_pose_ = parameter.as_bool();
1166 }
else if (param_name ==
"first_map_only") {
1167 first_map_only_ = parameter.as_bool();
1169 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
1170 if (param_name ==
"max_beams") {
1171 max_beams_ = parameter.as_int();
1172 reinit_laser =
true;
1173 }
else if (param_name ==
"max_particles") {
1174 max_particles_ = parameter.as_int();
1176 }
else if (param_name ==
"min_particles") {
1177 min_particles_ = parameter.as_int();
1179 }
else if (param_name ==
"resample_interval") {
1180 resample_interval_ = parameter.as_int();
1191 initParticleFilter();
1196 motion_model_.reset();
1203 lasers_update_.clear();
1204 frame_to_laser_.clear();
1205 laser_scan_connection_.disconnect();
1206 laser_scan_filter_.reset();
1207 laser_scan_sub_.reset();
1209 initMessageFilters();
1215 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1217 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1),
1223 AmclNode::mapReceived(
const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
1225 RCLCPP_DEBUG(get_logger(),
"AmclNode: A new map was received.");
1226 if (!nav2::validateMsg(*msg)) {
1227 RCLCPP_ERROR(get_logger(),
"Received map message is malformed. Rejecting.");
1230 if (first_map_only_ && first_map_received_) {
1233 handleMapMessage(*msg);
1234 first_map_received_ =
true;
1238 AmclNode::handleMapMessage(
const nav_msgs::msg::OccupancyGrid & msg)
1240 std::lock_guard<std::recursive_mutex> cfl(mutex_);
1243 get_logger(),
"Received a %d X %d map @ %.3f m/pix",
1246 msg.info.resolution);
1247 if (msg.header.frame_id != global_frame_id_) {
1249 get_logger(),
"Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could"
1250 " cause issues with reading published topics",
1251 msg.header.frame_id.c_str(),
1252 global_frame_id_.c_str());
1254 freeMapDependentMemory();
1255 map_ = convertMap(msg);
1257 #if NEW_UNIFORM_SAMPLING
1258 createFreeSpaceVector();
1263 AmclNode::createFreeSpaceVector()
1265 int delta = freespace_downsampling_ ? 2 : 1;
1267 free_space_indices.resize(0);
1268 for (
int i = 0; i < map_->size_x; i += delta) {
1269 for (
int j = 0; j < map_->size_y; j += delta) {
1270 if (map_->cells[MAP_INDEX(map_, i, j)].occ_state == -1) {
1271 AmclNode::Point2D point = {i, j};
1272 free_space_indices.push_back(point);
1279 AmclNode::freeMapDependentMemory()
1289 lasers_update_.clear();
1290 frame_to_laser_.clear();
1296 AmclNode::convertMap(
const nav_msgs::msg::OccupancyGrid & map_msg)
1298 map_t * map = map_alloc();
1300 map->size_x = map_msg.info.width;
1301 map->size_y = map_msg.info.height;
1302 map->scale = map_msg.info.resolution;
1303 map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale;
1304 map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale;
1310 for (
int i = 0; i < map->size_x * map->size_y; i++) {
1311 if (map_msg.data[i] == 0) {
1312 map->cells[i].occ_state = -1;
1313 }
else if (map_msg.data[i] == 100) {
1314 map->cells[i].occ_state = +1;
1316 map->cells[i].occ_state = 0;
1324 AmclNode::initTransforms()
1326 RCLCPP_INFO(get_logger(),
"initTransforms");
1329 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
1330 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
1331 get_node_base_interface(),
1332 get_node_timers_interface(),
1334 tf_buffer_->setCreateTimerInterface(timer_interface);
1335 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_,
this,
true);
1336 tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
1338 sent_first_transform_ =
false;
1339 latest_tf_valid_ =
false;
1340 latest_tf_ = tf2::Transform::getIdentity();
1344 AmclNode::initMessageFilters()
1346 auto sub_opt = rclcpp::SubscriptionOptions();
1347 sub_opt.callback_group = callback_group_;
1349 #if RCLCPP_VERSION_GTE(29, 6, 0)
1350 laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
1353 laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
1354 rclcpp_lifecycle::LifecycleNode>>(
1355 std::static_pointer_cast<rclcpp_lifecycle::LifecycleNode>(shared_from_this()),
1359 laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
1360 *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
1361 get_node_logging_interface(),
1362 get_node_clock_interface(),
1363 transform_tolerance_);
1366 laser_scan_connection_ = laser_scan_filter_->registerCallback(
1367 std::bind(&AmclNode::laserReceived,
this, std::placeholders::_1));
1371 AmclNode::initPubSub()
1373 RCLCPP_INFO(get_logger(),
"initPubSub");
1375 particle_cloud_pub_ = create_publisher<nav2_msgs::msg::ParticleCloud>(
1379 pose_pub_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
1383 initial_pose_sub_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
1385 std::bind(&AmclNode::initialPoseReceived,
this, std::placeholders::_1));
1387 map_sub_ = create_subscription<nav_msgs::msg::OccupancyGrid>(
1389 std::bind(&AmclNode::mapReceived,
this, std::placeholders::_1),
1392 RCLCPP_INFO(get_logger(),
"Subscribed to map topic.");
1396 AmclNode::initServices()
1398 global_loc_srv_ = create_service<std_srvs::srv::Empty>(
1399 "reinitialize_global_localization",
1400 std::bind(&AmclNode::globalLocalizationCallback,
this, std::placeholders::_1,
1401 std::placeholders::_2, std::placeholders::_3));
1403 initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
1405 std::bind(&AmclNode::initialPoseReceivedSrv,
this, std::placeholders::_1, std::placeholders::_2,
1406 std::placeholders::_3));
1408 nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
1409 "request_nomotion_update",
1410 std::bind(&AmclNode::nomotionUpdateCallback,
this, std::placeholders::_1, std::placeholders::_2,
1411 std::placeholders::_3));
1415 AmclNode::initOdometry()
1421 init_pose_[0] = last_published_pose_.pose.pose.position.x;
1422 init_pose_[1] = last_published_pose_.pose.pose.position.y;
1423 init_pose_[2] = tf2::getYaw(last_published_pose_.pose.pose.orientation);
1425 if (!initial_pose_is_known_) {
1426 init_cov_[0] = 0.5 * 0.5;
1427 init_cov_[1] = 0.5 * 0.5;
1428 init_cov_[2] = (M_PI / 12.0) * (M_PI / 12.0);
1430 init_cov_[0] = last_published_pose_.pose.covariance[0];
1431 init_cov_[1] = last_published_pose_.pose.covariance[7];
1432 init_cov_[2] = last_published_pose_.pose.covariance[35];
1435 motion_model_ = plugin_loader_.createSharedInstance(robot_model_type_);
1436 motion_model_->initialize(alpha1_, alpha2_, alpha3_, alpha4_, alpha5_);
1438 latest_odom_pose_ = geometry_msgs::msg::PoseStamped();
1442 AmclNode::initParticleFilter()
1446 min_particles_, max_particles_, alpha_slow_, alpha_fast_,
1447 (pf_init_model_fn_t)AmclNode::uniformPoseGenerator);
1448 pf_->pop_err = pf_err_;
1453 pf_init_pose_mean.v[0] = init_pose_[0];
1454 pf_init_pose_mean.v[1] = init_pose_[1];
1455 pf_init_pose_mean.v[2] = init_pose_[2];
1458 pf_init_pose_cov.m[0][0] = init_cov_[0];
1459 pf_init_pose_cov.m[1][1] = init_cov_[1];
1460 pf_init_pose_cov.m[2][2] = init_cov_[2];
1462 pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov);
1465 resample_count_ = 0;
1466 memset(&pf_odom_pose_, 0,
sizeof(pf_odom_pose_));
1470 AmclNode::initLaserScan()
1472 scan_error_count_ = 0;
1473 last_laser_received_ts_ = rclcpp::Time(0);
1478 #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.