diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 325c7e860a25e..ae8fca491cdc5 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -131,7 +131,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio "~/input/external_intersection_states", 10, std::bind(&BehaviorVelocityPlannerNode::onExternalIntersectionStates, this, _1)); sub_external_velocity_limit_ = this->create_subscription( - "~/input/external_velocity_limit_mps", 1, + "~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(), std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1)); sub_external_traffic_signals_ = this->create_subscription(