diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 596b90b15266e..57bf8e364c9af 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -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( - "~/input/vector_map", rclcpp::QoS{1}.transient_local(), + "~/input/vector_map", qos_transient_local, std::bind(&BehaviorPathPlannerNode::onMap, this, _1)); route_subscriber_ = create_subscription( - "~/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("~/output/path", 1); diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index 478e069539cbe..e3ad37c1ef87f 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -233,7 +233,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti // Subscribers { route_sub_ = create_subscription( - "~/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( "~/input/occupancy_grid", 1, std::bind(&FreespacePlannerNode::onOccupancyGrid, this, _1)); scenario_sub_ = create_subscription(