diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp index a96587c4465d6..a5f9badd9f4f7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp @@ -31,10 +31,7 @@ #include #include #include -#include -#include #include -#include #include #include @@ -76,7 +73,6 @@ struct PlannerData std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states; // velocity smoother std::shared_ptr velocity_smoother_; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md index 494446828e134..01062f81e77a2 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md @@ -17,17 +17,16 @@ This means that to stop before a wall, a stop point is inserted in the trajector ## Input topics -| Name | Type | Description | -| -------------------------------------- | ----------------------------------------------------- | ----------------------------- | -| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory | -| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | -| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity | -| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration | -| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects | -| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | -| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states | -| `~/input/virtual_traffic_light_states` | tier4_v2x_msgs::msg::VirtualTrafficLightStateArray | virtual traffic light states | -| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid | +| Name | Type | Description | +| ------------------------------ | ----------------------------------------------------- | ----------------------------- | +| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory | +| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map | +| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity | +| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration | +| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects | +| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | +| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states | +| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid | ## Output topics diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml index 3732d86ef380a..963394323caeb 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml @@ -24,7 +24,6 @@ - diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 96865fec1c197..586d27f2c9614 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -185,9 +185,6 @@ bool MotionVelocityPlannerNode::update_planner_data( // optional data const auto traffic_signals_ptr = sub_traffic_signals_.takeData(); if (traffic_signals_ptr) process_traffic_signals(traffic_signals_ptr); - const auto virtual_traffic_light_states_ptr = sub_virtual_traffic_light_states_.takeData(); - if (virtual_traffic_light_states_ptr) - planner_data_.virtual_traffic_light_states = *virtual_traffic_light_states_ptr; processing_times["update_planner_data.traffic_lights"] = sw.toc(true); return is_ready; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp index 757be518e018a..6e33b89e026c3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -80,9 +80,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber< autoware_perception_msgs::msg::TrafficLightGroupArray> sub_traffic_signals_{this, "~/input/traffic_signals"}; - autoware::universe_utils::InterProcessPollingSubscriber< - tier4_v2x_msgs::msg::VirtualTrafficLightStateArray> - sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"}; rclcpp::Subscription::SharedPtr sub_lanelet_map_; void on_trajectory( diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp index 44ff7820c1566..89a732ead861b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp @@ -101,8 +101,6 @@ void publishMandatoryTopics( test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map"); test_manager->publishTrafficSignals( test_target_node, "motion_velocity_planner_node/input/traffic_signals"); - test_manager->publishVirtualTrafficLightState( - test_target_node, "motion_velocity_planner_node/input/virtual_traffic_light_states"); test_manager->publishOccupancyGrid( test_target_node, "motion_velocity_planner_node/input/occupancy_grid"); }