Skip to content

Commit

Permalink
perf(autoware_ar_tag_based_localizer): remove unnecessary pub/sub dep…
Browse files Browse the repository at this point in the history
…th for transient_local (autowarefoundation#8259)
  • Loading branch information
KYabuuchi authored and esteve committed Aug 13, 2024
1 parent 189567c commit a5f717c
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options)
*/
using std::placeholders::_1;
map_bin_sub_ = this->create_subscription<LaneletMapBin>(
"~/input/lanelet2_map", rclcpp::QoS(10).durability(rclcpp::DurabilityPolicy::TransientLocal),
"~/input/lanelet2_map", rclcpp::QoS(1).durability(rclcpp::DurabilityPolicy::TransientLocal),
std::bind(&ArTagBasedLocalizer::map_bin_callback, this, _1));

rclcpp::QoS qos_sub(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
Expand All @@ -131,7 +131,7 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options)
/*
Publishers
*/
const rclcpp::QoS qos_pub_once = rclcpp::QoS(rclcpp::KeepLast(10)).transient_local().reliable();
const rclcpp::QoS qos_pub_once = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
const rclcpp::QoS qos_pub_periodic(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default));
pose_pub_ = this->create_publisher<PoseWithCovarianceStamped>(
"~/output/pose_with_covariance", qos_pub_periodic);
Expand Down

0 comments on commit a5f717c

Please sign in to comment.