From 6af889fb194418f8d9d7280027eeca488136e3b4 Mon Sep 17 00:00:00 2001 From: liuXinGangChina Date: Fri, 21 Feb 2025 11:19:31 +0800 Subject: [PATCH] feat(autoware_velocity_smoother):porting from universe to core, autoware_velocity_smoother, solve dependency conflict which use tier4 planning velocity limit msg: v0.2 Signed-off-by: liuXinGangChina --- .../autoware/obstacle_cruise_planner/type_alias.hpp | 8 ++++---- planning/autoware_obstacle_cruise_planner/package.xml | 1 + planning/autoware_obstacle_stop_planner/package.xml | 1 + planning/autoware_obstacle_stop_planner/src/node.hpp | 8 ++++---- .../package.xml | 1 + .../src/remaining_distance_time_calculator_node.cpp | 2 +- .../src/remaining_distance_time_calculator_node.hpp | 4 ++-- planning/autoware_surround_obstacle_checker/README.md | 4 ++-- .../autoware_surround_obstacle_checker/package.xml | 2 +- .../autoware_surround_obstacle_checker/src/node.hpp | 8 ++++---- .../surround_obstacle_checker-design.ja.md | 4 ++-- .../include/autoware/velocity_smoother/node.hpp | 4 ++-- planning/autoware_velocity_smoother/package.xml | 2 +- .../test/test_velocity_smoother_node_interface.cpp | 2 +- .../autoware/behavior_velocity_planner/node.hpp | 4 ++-- .../autoware_behavior_velocity_planner/package.xml | 2 +- .../src/test_utils.cpp | 2 +- .../behavior_velocity_planner_common/planner_data.hpp | 4 ++-- .../package.xml | 2 +- .../test/src/test_trajectory_utils.cpp | 2 +- .../package.xml | 1 + .../src/type_alias.hpp | 8 ++++---- .../package.xml | 1 + .../src/type_alias.hpp | 8 ++++---- .../velocity_planning_result.hpp | 8 ++++---- .../package.xml | 1 + .../package.xml | 1 + .../src/node.hpp | 8 ++++---- .../autoware_mrm_comfortable_stop_operator/README.md | 4 ++-- .../mrm_comfortable_stop_operator_core.hpp | 10 +++++----- .../autoware_mrm_comfortable_stop_operator/package.xml | 2 +- .../mrm_comfortable_stop_operator_core.cpp | 8 ++++---- .../autoware_overlay_rviz_plugin/CMakeLists.txt | 2 +- .../autoware_overlay_rviz_plugin/README.md | 2 +- .../include/signal_display.hpp | 4 ++-- .../include/speed_limit_display.hpp | 4 ++-- .../autoware_overlay_rviz_plugin/package.xml | 2 +- .../src/signal_display.cpp | 8 ++++---- .../src/speed_limit_display.cpp | 2 +- visualization/tier4_planning_rviz_plugin/package.xml | 2 +- .../src/tools/max_velocity.cpp | 4 ++-- .../src/tools/max_velocity.hpp | 8 ++++---- visualization/tier4_state_rviz_plugin/README.md | 2 +- visualization/tier4_state_rviz_plugin/package.xml | 2 +- .../src/autoware_state_panel.cpp | 4 ++-- .../src/include/autoware_state_panel.hpp | 4 ++-- 46 files changed, 92 insertions(+), 85 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index e1fb9a250a59e..f607b8922f49c 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -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 @@ -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; diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index c70c8ce6f710f..f2aa2e324d52e 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -42,6 +42,7 @@ tier4_metric_msgs tier4_planning_msgs visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index d0e3a0f7e2f82..5da8c061cc805 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -44,6 +44,7 @@ tf2_ros tier4_planning_msgs visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_obstacle_stop_planner/src/node.hpp b/planning/autoware_obstacle_stop_planner/src/node.hpp index a48c8c9ba53ac..5b9ce134f9bc4 100644 --- a/planning/autoware_obstacle_stop_planner/src/node.hpp +++ b/planning/autoware_obstacle_stop_planner/src/node.hpp @@ -42,8 +42,8 @@ #include #include #include -#include -#include +#include +#include #include #include @@ -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; using PointCloud = pcl::PointCloud; diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 25a223fbd7a3c..75aaa5cd1a81e 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -25,6 +25,7 @@ rclcpp_components std_msgs tier4_planning_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp index 74f3f2f43077d..52ed083a21ef4 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -55,7 +55,7 @@ RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( sub_route_ = create_subscription( "~/input/route", qos_transient_local, std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1)); - sub_planning_velocity_ = create_subscription( + sub_planning_velocity_ = create_subscription( "/planning/scenario_planning/current_max_velocity", qos_transient_local, std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); sub_scenario_ = this->create_subscription( diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index 8a38941d383ee..019834b631f7f 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -26,7 +26,7 @@ #include #include #include -#include +#include #include #include @@ -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::SharedPtr sub_route_; diff --git a/planning/autoware_surround_obstacle_checker/README.md b/planning/autoware_surround_obstacle_checker/README.md index fbe749f2eec08..0251c5317820f 100644 --- a/planning/autoware_surround_obstacle_checker/README.md +++ b/planning/autoware_surround_obstacle_checker/README.md @@ -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 | diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index e5ee999aa24d8..1ecb8e2f0dae9 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -34,8 +34,8 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_planning_msgs visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index b6d6bffefed1a..e6da5d081687f 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -30,8 +30,8 @@ #include #include #include -#include -#include +#include +#include #include #include @@ -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; diff --git a/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md b/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md index b19f556e59830..83b417e6d9802 100644 --- a/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md +++ b/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md @@ -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 | diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index c5685e5b500be..f2915640c5fe4 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -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 @@ -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 diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index d25889fa551f7..13bf96fe7dd8a 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -35,7 +35,7 @@ rclcpp tf2 tf2_ros - tier4_planning_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp index d8a424095fcc8..c54f375f1ec01 100644 --- a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp +++ b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp @@ -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{}); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp index 2f267131ef1be..215fc9a1329eb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/include/autoware/behavior_velocity_planner/node.hpp @@ -31,7 +31,7 @@ #include #include #include -#include +#include #include #include @@ -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 { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index d68937727773f..ba2d808e7f02b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -55,7 +55,7 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_planning_msgs + autoware_internal_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp index 45ce88c8e92d4..c92a210ac499d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp @@ -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()); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp index f8b37999cb6bf..cd89142876dc9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp @@ -29,7 +29,7 @@ #include #include #include -#include +#include #include #include @@ -62,7 +62,7 @@ struct PlannerData std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; - std::optional external_velocity_limit; + std::optional external_velocity_limit; bool is_simulation = false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index a66faa2e0a303..77ed1d3879601 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -45,7 +45,7 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_planning_msgs + autoware_internal_planning_msgs visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp index 283e54c01403b..ae4d24812011b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp @@ -77,7 +77,7 @@ TEST(smoothPath, nominal) planner_data->velocity_smoother_ = std::make_shared( - *node, std::make_shared()); + *node, std::make_shared()); // Input path PathWithLaneId in_path; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/package.xml index e0cbf2c193b7a..9dbbcf2680d64 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/package.xml @@ -30,6 +30,7 @@ tier4_metric_msgs tier4_planning_msgs visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/type_alias.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/type_alias.hpp index 673574c24a914..00ae360faba44 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/type_alias.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_cruise_module/src/type_alias.hpp @@ -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 #include @@ -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; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/package.xml index aa1ec002ce5cc..4b540c879d8a0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/package.xml @@ -29,6 +29,7 @@ tier4_metric_msgs tier4_planning_msgs visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/src/type_alias.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/src/type_alias.hpp index 673574c24a914..00ae360faba44 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/src/type_alias.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_slow_down_module/src/type_alias.hpp @@ -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 #include @@ -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; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp index 4faeb698e2bcd..70ba77557f7ef 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/include/autoware/motion_velocity_planner_common_universe/velocity_planning_result.hpp @@ -18,8 +18,8 @@ #include #include -#include -#include +#include +#include #include #include @@ -44,8 +44,8 @@ struct VelocityPlanningResult { std::vector stop_points{}; std::vector slowdown_intervals{}; - std::optional velocity_limit{std::nullopt}; - std::optional velocity_limit_clear_command{ + std::optional velocity_limit{std::nullopt}; + std::optional velocity_limit_clear_command{ std::nullopt}; }; } // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml index 214e69f4122a2..11c77c53bbedb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/package.xml @@ -32,6 +32,7 @@ libboost-dev rclcpp visualization_msgs + autoware_internal_planning_msgs ament_cmake_ros ament_lint_auto diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml index 570e6822ce2cf..9dc030d67d1d2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/package.xml @@ -42,6 +42,7 @@ tf2_ros tier4_metric_msgs visualization_msgs + autoware_internal_planning_msgs rosidl_default_runtime diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp index dee10e94ee64f..5cf0f24a7734f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/src/node.hpp @@ -33,8 +33,8 @@ #include #include #include -#include -#include +#include +#include #include #include @@ -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; class MotionVelocityPlannerNode : public rclcpp::Node diff --git a/system/autoware_mrm_comfortable_stop_operator/README.md b/system/autoware_mrm_comfortable_stop_operator/README.md index dffa28f1dfa49..5f2bbdc122192 100644 --- a/system/autoware_mrm_comfortable_stop_operator/README.md +++ b/system/autoware_mrm_comfortable_stop_operator/README.md @@ -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 diff --git a/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp b/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp index 0dbaef1f1df21..41ff04e341a5f 100644 --- a/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp +++ b/system/autoware_mrm_comfortable_stop_operator/include/autoware/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp @@ -20,9 +20,9 @@ #include // Autoware -#include -#include -#include +#include +#include +#include #include #include @@ -61,8 +61,8 @@ class MrmComfortableStopOperator : public rclcpp::Node // Publisher rclcpp::Publisher::SharedPtr pub_status_; - rclcpp::Publisher::SharedPtr pub_velocity_limit_; - rclcpp::Publisher::SharedPtr + rclcpp::Publisher::SharedPtr pub_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_clear_command_; void publishStatus() const; diff --git a/system/autoware_mrm_comfortable_stop_operator/package.xml b/system/autoware_mrm_comfortable_stop_operator/package.xml index 33746a7d2dda0..6dab69b366be1 100644 --- a/system/autoware_mrm_comfortable_stop_operator/package.xml +++ b/system/autoware_mrm_comfortable_stop_operator/package.xml @@ -18,7 +18,7 @@ rclcpp_components std_msgs std_srvs - tier4_planning_msgs + autoware_internal_planning_msgs tier4_system_msgs ament_lint_auto diff --git a/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp b/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp index 397367e568a25..c6ac90c4fb9d2 100644 --- a/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +++ b/system/autoware_mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp @@ -39,10 +39,10 @@ MrmComfortableStopOperator::MrmComfortableStopOperator(const rclcpp::NodeOptions // Publisher pub_status_ = create_publisher( "~/output/mrm/comfortable_stop/status", 1); - pub_velocity_limit_ = create_publisher( + pub_velocity_limit_ = create_publisher( "~/output/velocity_limit", rclcpp::QoS{1}.transient_local()); pub_velocity_limit_clear_command_ = - create_publisher( + create_publisher( "~/output/velocity_limit/clear", rclcpp::QoS{1}.transient_local()); // Timer @@ -96,7 +96,7 @@ void MrmComfortableStopOperator::publishStatus() const void MrmComfortableStopOperator::publishVelocityLimit() const { - auto velocity_limit = tier4_planning_msgs::msg::VelocityLimit(); + auto velocity_limit = autoware_internal_planning_msgs::msg::VelocityLimit(); velocity_limit.stamp = this->now(); velocity_limit.max_velocity = 0; velocity_limit.use_constraints = true; @@ -110,7 +110,7 @@ void MrmComfortableStopOperator::publishVelocityLimit() const void MrmComfortableStopOperator::publishVelocityLimitClearCommand() const { - auto velocity_limit_clear_command = tier4_planning_msgs::msg::VelocityLimitClearCommand(); + auto velocity_limit_clear_command = autoware_internal_planning_msgs::msg::VelocityLimitClearCommand(); velocity_limit_clear_command.stamp = this->now(); velocity_limit_clear_command.command = true; velocity_limit_clear_command.sender = "mrm_comfortable_stop_operator"; diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt index 95224b9967d4b..f8b88c96016f8 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt @@ -69,7 +69,7 @@ ament_target_dependencies(${PROJECT_NAME} PUBLIC rviz_common rviz_rendering autoware_vehicle_msgs - tier4_planning_msgs + autoware_internal_planning_msgs autoware_perception_msgs ) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md index 943d566ad109c..fbe492fdbaeb1 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md @@ -20,7 +20,7 @@ This plugin provides a visual and easy-to-understand display of vehicle speed, t | `/vehicle/status/hazard_status` | `autoware_vehicle_msgs::msg::HazardReport` | The topic is status of hazard | | `/vehicle/status/steering_status` | `autoware_vehicle_msgs::msg::SteeringReport` | The topic is status of steering | | `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | The topic is status of gear | -| `/planning/scenario_planning/current_max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | The topic is velocity limit | +| `/planning/scenario_planning/current_max_velocity` | `autoware_internal_planning_msgs::msg::VelocityLimit` | The topic is velocity limit | | `/perception/traffic_light_recognition/traffic_signals` | `autoware_perception_msgs::msg::TrafficLightGroupArray` | The topic is status of traffic light | ## Parameter diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp index f8d822473c415..e7426a80c9024 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp @@ -110,7 +110,7 @@ private Q_SLOTS: rclcpp::Subscription::SharedPtr hazard_lights_sub_; rclcpp::Subscription::SharedPtr traffic_sub_; - rclcpp::Subscription::SharedPtr speed_limit_sub_; + rclcpp::Subscription::SharedPtr speed_limit_sub_; std::mutex property_mutex_; @@ -121,7 +121,7 @@ private Q_SLOTS: const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr & msg); void updateHazardLightsData( const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & msg); - void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); + void updateSpeedLimitData(const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); void updateTrafficLightData( const autoware_perception_msgs::msg::TrafficLightGroup::ConstSharedPtr msg); void drawWidget(QImage & hud); diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp index c88984a4c339f..16707f78adfb0 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp @@ -24,7 +24,7 @@ #include #include "autoware_vehicle_msgs/msg/velocity_report.hpp" -#include +#include "autoware_internal_planning_msgs/msg/velocity_limit.hpp" #include #include @@ -41,7 +41,7 @@ class SpeedLimitDisplay QPainter & painter, const QRectF & backgroundRect, const QColor & color, const QColor & light_color, const QColor & dark_color, const QColor & bg_color, const float bg_alpha); - void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); + void updateSpeedLimitData(const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); void updateSpeedData(const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr & msg); private: diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml index fed43c91ddcdb..4eeae729c3b55 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml @@ -18,7 +18,7 @@ rviz_common rviz_ogre_vendor rviz_rendering - tier4_planning_msgs + autoware_internal_planning_msgs ament_lint_auto autoware_lint_common diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp index 270d1837f2dba..402c63341629c 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp @@ -121,7 +121,7 @@ void SignalDisplay::onInitialize() speed_limit_topic_property_ = std::make_unique( "Speed Limit Topic", "/planning/scenario_planning/current_max_velocity", - "tier4_planning_msgs/msg/VelocityLimit", "Topic for Speed Limit Data", this, + "autoware_internal_planning_msgs/msg/VelocityLimit", "Topic for Speed Limit Data", this, SLOT(topic_updated_speed_limit())); speed_limit_topic_property_->initialize(rviz_ros_node); @@ -217,7 +217,7 @@ void SignalDisplay::updateTrafficLightData( } void SignalDisplay::updateSpeedLimitData( - const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) + const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { std::lock_guard lock(property_mutex_); @@ -438,10 +438,10 @@ void SignalDisplay::topic_updated_speed_limit() speed_limit_sub_.reset(); auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); speed_limit_sub_ = - rviz_ros_node->get_raw_node()->create_subscription( + rviz_ros_node->get_raw_node()->create_subscription( speed_limit_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)).transient_local(), - [this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { + [this](const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { updateSpeedLimitData(msg); }); } diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp index 36b5212c08f75..eeeaf2bdaa9cb 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp @@ -52,7 +52,7 @@ SpeedLimitDisplay::SpeedLimitDisplay() : current_limit(0.0), current_speed_(0.0) } void SpeedLimitDisplay::updateSpeedLimitData( - const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) + const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { current_limit = msg->max_velocity; } diff --git a/visualization/tier4_planning_rviz_plugin/package.xml b/visualization/tier4_planning_rviz_plugin/package.xml index 352e3bfbf5840..418f591b3bb48 100644 --- a/visualization/tier4_planning_rviz_plugin/package.xml +++ b/visualization/tier4_planning_rviz_plugin/package.xml @@ -25,7 +25,7 @@ rviz_rendering tf2_geometry_msgs tf2_ros - tier4_planning_msgs + autoware_internal_planning_msgs ament_lint_auto autoware_lint_common diff --git a/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp index 098be3a93ddd0..a47aadfb2ddae 100644 --- a/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp +++ b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp @@ -116,7 +116,7 @@ void MaxVelocityDisplay::subscribe() std::string topic_name = property_topic_name_->getStdString(); if (topic_name.length() > 0 && topic_name != "/") { rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - max_vel_sub_ = raw_node->create_subscription( + max_vel_sub_ = raw_node->create_subscription( topic_name, rclcpp::QoS{1}.transient_local(), std::bind(&MaxVelocityDisplay::processMessage, this, std::placeholders::_1)); } @@ -128,7 +128,7 @@ void MaxVelocityDisplay::unsubscribe() } void MaxVelocityDisplay::processMessage( - const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr) + const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr) { if (!overlay_->isVisible()) { return; diff --git a/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp index 9098d37e4f7a0..4f6a917aa87e6 100644 --- a/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp +++ b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp @@ -34,7 +34,7 @@ #include #include -#include +#include #include #include @@ -63,7 +63,7 @@ private Q_SLOTS: void updateVisualization(); protected: - void processMessage(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr); + void processMessage(const autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr); jsk_rviz_plugins::OverlayObject::Ptr overlay_; rviz_common::properties::ColorProperty * property_text_color_; rviz_common::properties::IntProperty * property_left_; @@ -73,8 +73,8 @@ private Q_SLOTS: rviz_common::properties::FloatProperty * property_value_scale_; private: - rclcpp::Subscription::SharedPtr max_vel_sub_; - tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr last_msg_ptr_; + rclcpp::Subscription::SharedPtr max_vel_sub_; + autoware_internal_planning_msgs::msg::VelocityLimit::ConstSharedPtr last_msg_ptr_; }; } // namespace rviz_plugins diff --git a/visualization/tier4_state_rviz_plugin/README.md b/visualization/tier4_state_rviz_plugin/README.md index e45be3bea13dc..0adcfe43923ee 100644 --- a/visualization/tier4_state_rviz_plugin/README.md +++ b/visualization/tier4_state_rviz_plugin/README.md @@ -31,7 +31,7 @@ This plugin also can engage from the panel. | `/api/routing/clear_route` | `autoware_adapi_v1_msgs::srv::ClearRoute` | The service to clear route state | | `/api/motion/accept_start` | `autoware_adapi_v1_msgs::srv::AcceptStart` | The service to accept the vehicle to start | | `/api/autoware/set/emergency` | `tier4_external_api_msgs::srv::SetEmergency` | The service to set external emergency | -| `/planning/scenario_planning/max_velocity_default` | `tier4_planning_msgs::msg::VelocityLimit` | The topic to set maximum speed of the vehicle | +| `/planning/scenario_planning/max_velocity_default` | `autoware_internal_planning_msgs::msg::VelocityLimit` | The topic to set maximum speed of the vehicle | ## HowToUse diff --git a/visualization/tier4_state_rviz_plugin/package.xml b/visualization/tier4_state_rviz_plugin/package.xml index 7b1f08ceef6eb..27889afb652fb 100644 --- a/visualization/tier4_state_rviz_plugin/package.xml +++ b/visualization/tier4_state_rviz_plugin/package.xml @@ -24,7 +24,7 @@ rviz_common tier4_control_msgs tier4_external_api_msgs - tier4_planning_msgs + autoware_internal_planning_msgs ament_lint_auto autoware_lint_common diff --git a/visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index ffcf801e758e0..ce04c370b61e2 100644 --- a/visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -149,7 +149,7 @@ void AutowareStatePanel::onInitialize() client_emergency_stop_ = raw_node_->create_client( "/api/autoware/set/emergency"); - pub_velocity_limit_ = raw_node_->create_publisher( + pub_velocity_limit_ = raw_node_->create_publisher( "/planning/scenario_planning/max_velocity_default", rclcpp::QoS{1}.transient_local()); QObject::connect(segmented_button, &CustomSegmentedButton::buttonClicked, this, [this](int id) { @@ -804,7 +804,7 @@ void AutowareStatePanel::onSwitchStateChanged(int state) void AutowareStatePanel::onClickVelocityLimit() { - auto velocity_limit = std::make_shared(); + auto velocity_limit = std::make_shared(); velocity_limit->stamp = raw_node_->now(); velocity_limit->max_velocity = velocity_limit_value_label_->text().toDouble() / 3.6; pub_velocity_limit_->publish(*velocity_limit); diff --git a/visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp b/visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp index 3c106467b9beb..16d4d0828fbfc 100644 --- a/visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp +++ b/visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp @@ -54,7 +54,7 @@ #include #include #include -#include +#include #include @@ -119,7 +119,7 @@ public Q_SLOTS: // NOLINT for Qt rclcpp::Client::SharedPtr client_emergency_stop_; rclcpp::Subscription::SharedPtr sub_emergency_; - rclcpp::Publisher::SharedPtr pub_velocity_limit_; + rclcpp::Publisher::SharedPtr pub_velocity_limit_; QLabel * velocity_limit_value_label_{nullptr}; bool sliderIsDragging = false;