Skip to content

Commit

Permalink
feat(autoware_velocity_smoother):porting from universe to core, autow…
Browse files Browse the repository at this point in the history
…are_velocity_smoother, solve dependency conflict which use tier4 planning velocity limit msg: v0.2

Signed-off-by: liuXinGangChina <lxg19892021@gmail.com>
  • Loading branch information
liuXinGangChina committed Feb 21, 2025
1 parent 6919960 commit 6af889f
Show file tree
Hide file tree
Showing 46 changed files with 92 additions and 85 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp"
#include "tier4_planning_msgs/msg/velocity_limit.hpp"
#include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

#include <pcl/point_cloud.h>
Expand All @@ -54,8 +54,8 @@ using geometry_msgs::msg::Twist;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tier4_planning_msgs::msg::StopSpeedExceeded;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
namespace bg = boost::geometry;
Expand Down
1 change: 1 addition & 0 deletions planning/autoware_obstacle_cruise_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
1 change: 1 addition & 0 deletions planning/autoware_obstacle_stop_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
8 changes: 4 additions & 4 deletions planning/autoware_obstacle_stop_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_planning_msgs/msg/expand_stop_range.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp>

#include <boost/assert.hpp>
#include <boost/assign/list_of.hpp>
Expand Down Expand Up @@ -90,8 +90,8 @@ using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using tier4_planning_msgs::msg::ExpandStopRange;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;

using TrajectoryPoints = std::vector<TrajectoryPoint>;
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode(
sub_route_ = create_subscription<LaneletRoute>(
"~/input/route", qos_transient_local,
std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1));
sub_planning_velocity_ = create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
sub_planning_velocity_ = create_subscription<autoware_internal_planning_msgs::msg::VelocityLimit>(
"/planning/scenario_planning/current_max_velocity", qos_transient_local,
std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1));
sub_scenario_ = this->create_subscription<tier4_planning_msgs::msg::Scenario>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <geometry_msgs/msg/vector3.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>

#include <lanelet2_core/Forward.h>
#include <lanelet2_core/utility/Optional.h>
Expand All @@ -49,7 +49,7 @@ class RemainingDistanceTimeCalculatorNode : public rclcpp::Node
using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute;
using HADMapBin = autoware_map_msgs::msg::LaneletMapBin;
using Odometry = nav_msgs::msg::Odometry;
using VelocityLimit = tier4_planning_msgs::msg::VelocityLimit;
using VelocityLimit = autoware_internal_planning_msgs::msg::VelocityLimit;
using MissionRemainingDistanceTime = autoware_internal_msgs::msg::MissionRemainingDistanceTime;

rclcpp::Subscription<LaneletRoute>::SharedPtr sub_route_;
Expand Down
4 changes: 2 additions & 2 deletions planning/autoware_surround_obstacle_checker/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ As mentioned in stop condition section, it prevents chattering by changing thres

| Name | Type | Description |
| --------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------------------------------- |
| `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |
| `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/velocity_limit_clear_command` | `autoware_internal_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |
| `~/output/max_velocity` | `autoware_internal_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason |
| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization |
| `~/debug/footprint` | `geometry_msgs::msg::PolygonStamped` | Ego vehicle base footprint for visualization |
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_surround_obstacle_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
8 changes: 4 additions & 4 deletions planning/autoware_surround_obstacle_checker/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
#include <diagnostic_msgs/msg/key_value.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <tf2/utils.h>
Expand All @@ -52,8 +52,8 @@ using autoware::motion_utils::VehicleStopChecker;
using autoware::vehicle_info_utils::VehicleInfo;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::Shape;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;

using Obstacle = std::pair<double /* distance */, geometry_msgs::msg::Point>;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ Stop condition の項で述べたように、状態によって障害物判定

| Name | Type | Description |
| --------------------------------------- | ----------------------------------------------------- | ---------------------------- |
| `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |
| `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/velocity_limit_clear_command` | `autoware_internal_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |
| `~/output/max_velocity` | `autoware_internal_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason |
| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization |

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary
#include "autoware_internal_planning_msgs/msg/velocity_limit.hpp" // temporary
#include "visualization_msgs/msg/marker_array.hpp"

#include <iostream>
Expand All @@ -69,7 +69,7 @@ using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
using nav_msgs::msg::Odometry;
using tier4_planning_msgs::msg::VelocityLimit; // temporary
using autoware_internal_planning_msgs::msg::VelocityLimit; // temporary
using visualization_msgs::msg::MarkerArray;

struct Motion
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_velocity_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ void publishMandatoryTopics(
test_target_node, "/localization/kinematic_state", autoware::test_utils::makeOdometry());
test_manager->publishInput(
test_target_node, "velocity_smoother/input/external_velocity_limit_mps",
tier4_planning_msgs::msg::VelocityLimit{});
autoware_internal_planning_msgs::msg::VelocityLimit{});
test_manager->publishInput(
test_target_node, "velocity_smoother/input/operation_mode_state",
autoware_adapi_v1_msgs::msg::OperationModeState{});
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <tf2_ros/buffer.h>
Expand All @@ -45,7 +45,7 @@
namespace autoware::behavior_velocity_planner
{
using autoware_map_msgs::msg::LaneletMapBin;
using tier4_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimit;

class BehaviorVelocityPlannerNode : public rclcpp::Node
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ void publishMandatoryTopics(
autoware_perception_msgs::msg::TrafficLightGroupArray{});
test_manager->publishInput(
test_target_node, "behavior_velocity_planner_node/input/external_velocity_limit_mps",
tier4_planning_msgs::msg::VelocityLimit{});
autoware_internal_planning_msgs::msg::VelocityLimit{});
test_manager->publishInput(
test_target_node, "behavior_velocity_planner_node/input/occupancy_grid",
autoware::test_utils::makeCostMapMsg());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/header.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
Expand Down Expand Up @@ -62,7 +62,7 @@ struct PlannerData

std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
std::optional<autoware_internal_planning_msgs::msg::VelocityLimit> external_velocity_limit;

bool is_simulation = false;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ TEST(smoothPath, nominal)

planner_data->velocity_smoother_ =
std::make_shared<autoware::velocity_smoother::JerkFilteredSmoother>(
*node, std::make_shared<autoware::universe_utils::TimeKeeper>());
*node, std::make_shared<autoware_utils::TimeKeeper>());

// Input path
PathWithLaneId in_path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#include "geometry_msgs/msg/twist.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "tier4_planning_msgs/msg/velocity_limit.hpp"
#include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>
Expand All @@ -53,8 +53,8 @@ using autoware_planning_msgs::msg::TrajectoryPoint;
using geometry_msgs::msg::Twist;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
namespace bg = boost::geometry;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#include "geometry_msgs/msg/twist.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "tier4_planning_msgs/msg/velocity_limit.hpp"
#include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit.hpp"
#include "autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include <tier4_metric_msgs/msg/metric.hpp>
#include <tier4_metric_msgs/msg/metric_array.hpp>
Expand All @@ -53,8 +53,8 @@ using autoware_planning_msgs::msg::TrajectoryPoint;
using geometry_msgs::msg::Twist;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
namespace bg = boost::geometry;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>

#include <geometry_msgs/msg/point.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <string>
Expand All @@ -44,8 +44,8 @@ struct VelocityPlanningResult
{
std::vector<geometry_msgs::msg::Point> stop_points{};
std::vector<SlowdownInterval> slowdown_intervals{};
std::optional<tier4_planning_msgs::msg::VelocityLimit> velocity_limit{std::nullopt};
std::optional<tier4_planning_msgs::msg::VelocityLimitClearCommand> velocity_limit_clear_command{
std::optional<autoware_internal_planning_msgs::msg::VelocityLimit> velocity_limit{std::nullopt};
std::optional<autoware_internal_planning_msgs::msg::VelocityLimitClearCommand> velocity_limit_clear_command{
std::nullopt};
};
} // namespace autoware::motion_velocity_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
<depend>libboost-dev</depend>
<depend>rclcpp</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>
<depend>visualization_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit.hpp>
#include <autoware_internal_planning_msgs/msg/velocity_limit_clear_command.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <tf2_ros/buffer.h>
Expand All @@ -52,8 +52,8 @@ using autoware_map_msgs::msg::LaneletMapBin;
using autoware_motion_velocity_planner_node_universe::srv::LoadPlugin;
using autoware_motion_velocity_planner_node_universe::srv::UnloadPlugin;
using autoware_planning_msgs::msg::Trajectory;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using autoware_internal_planning_msgs::msg::VelocityLimit;
using autoware_internal_planning_msgs::msg::VelocityLimitClearCommand;
using TrajectoryPoints = std::vector<autoware_planning_msgs::msg::TrajectoryPoint>;

class MotionVelocityPlannerNode : public rclcpp::Node
Expand Down
4 changes: 2 additions & 2 deletions system/autoware_mrm_comfortable_stop_operator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ MRM comfortable stop operator is a node that generates comfortable stop commands
| Name | Type | Description |
| -------------------------------------- | ----------------------------------------------------- | ---------------------------- |
| `~/output/mrm/comfortable_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | MRM execution status |
| `~/output/velocity_limit` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/velocity_limit/clear` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |
| `~/output/velocity_limit` | `autoware_internal_planning_msgs::msg::VelocityLimit` | Velocity limit command |
| `~/output/velocity_limit/clear` | `autoware_internal_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command |

## Parameters

Expand Down
Loading

0 comments on commit 6af889f

Please sign in to comment.