Skip to content

Commit

Permalink
fix(route): set transient_local for route subscriber (#674)
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe authored Apr 12, 2022
1 parent 36165da commit dc682e6
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,12 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
"~/input/force_approval", 1, std::bind(&BehaviorPathPlannerNode::onForceApproval, this, _1));

// route_handler
auto qos_transient_local = rclcpp::QoS{1}.transient_local();
vector_map_subscriber_ = create_subscription<HADMapBin>(
"~/input/vector_map", rclcpp::QoS{1}.transient_local(),
"~/input/vector_map", qos_transient_local,
std::bind(&BehaviorPathPlannerNode::onMap, this, _1));
route_subscriber_ = create_subscription<HADMapRoute>(
"~/input/route", 1, std::bind(&BehaviorPathPlannerNode::onRoute, this, _1));
"~/input/route", qos_transient_local, std::bind(&BehaviorPathPlannerNode::onRoute, this, _1));

// publisher
path_publisher_ = create_publisher<PathWithLaneId>("~/output/path", 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti
// Subscribers
{
route_sub_ = create_subscription<HADMapRoute>(
"~/input/route", 1, std::bind(&FreespacePlannerNode::onRoute, this, _1));
"~/input/route", rclcpp::QoS{1}.transient_local(),
std::bind(&FreespacePlannerNode::onRoute, this, _1));
occupancy_grid_sub_ = create_subscription<OccupancyGrid>(
"~/input/occupancy_grid", 1, std::bind(&FreespacePlannerNode::onOccupancyGrid, this, _1));
scenario_sub_ = create_subscription<Scenario>(
Expand Down

0 comments on commit dc682e6

Please sign in to comment.