Skip to content

Commit 0b22bb4

Browse files
anaelle-swasarazin
andauthored
add polygon_subscribe_transient_local parameter in collision monitor (#4207)
Signed-off-by: asarazin <[email protected]> Co-authored-by: asarazin <[email protected]>
1 parent f9828c2 commit 0b22bb4

File tree

2 files changed

+9
-0
lines changed

2 files changed

+9
-0
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -246,6 +246,8 @@ class Polygon
246246
double simulation_time_step_;
247247
/// @brief Whether polygon is enabled
248248
bool enabled_;
249+
/// @brief Wether the subscription to polygon topic has transient local QoS durability
250+
bool polygon_subscribe_transient_local_;
249251
/// @brief Polygon subscription
250252
rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_sub_;
251253
/// @brief Footprint subscriber

nav2_collision_monitor/src/polygon.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,9 @@ bool Polygon::configure()
7171
"[%s]: Subscribing on %s topic for polygon",
7272
polygon_name_.c_str(), polygon_sub_topic.c_str());
7373
rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default
74+
if (polygon_subscribe_transient_local_) {
75+
polygon_qos.transient_local();
76+
}
7477
polygon_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
7578
polygon_sub_topic, polygon_qos,
7679
std::bind(&Polygon::polygonCallback, this, std::placeholders::_1));
@@ -432,6 +435,10 @@ bool Polygon::getParameters(
432435
footprint_topic =
433436
node->get_parameter(polygon_name_ + ".footprint_topic").as_string();
434437
}
438+
nav2_util::declare_parameter_if_not_declared(
439+
node, polygon_name_ + ".polygon_subscribe_transient_local", rclcpp::ParameterValue(false));
440+
polygon_subscribe_transient_local_ =
441+
node->get_parameter(polygon_name_ + ".polygon_subscribe_transient_local").as_bool();
435442
} catch (const std::exception & ex) {
436443
RCLCPP_ERROR(
437444
logger_,

0 commit comments

Comments
 (0)