Skip to content

Commit 6ed5634

Browse files
authoredDec 19, 2024··
feat(motion_velocity_planner): remove unnecessary tier4_api_msgs and tier4_v2x_msgs (autowarefoundation#9691)
* feat(motion_velocity_planner): remove unnecessary tier4_api_msgs and tier4_v2x_msgs Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 3abb7bc commit 6ed5634

File tree

6 files changed

+10
-24
lines changed

6 files changed

+10
-24
lines changed
 

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -31,10 +31,7 @@
3131
#include <nav_msgs/msg/odometry.hpp>
3232
#include <sensor_msgs/msg/point_cloud2.hpp>
3333
#include <std_msgs/msg/header.hpp>
34-
#include <tier4_api_msgs/msg/crosswalk_status.hpp>
35-
#include <tier4_api_msgs/msg/intersection_status.hpp>
3634
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
37-
#include <tier4_v2x_msgs/msg/virtual_traffic_light_state_array.hpp>
3835

3936
#include <lanelet2_core/Forward.h>
4037
#include <pcl/point_cloud.h>
@@ -76,7 +73,6 @@ struct PlannerData
7673
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
7774
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
7875
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
79-
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray virtual_traffic_light_states;
8076

8177
// velocity smoother
8278
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md

+10-11
Original file line numberDiff line numberDiff line change
@@ -17,17 +17,16 @@ This means that to stop before a wall, a stop point is inserted in the trajector
1717

1818
## Input topics
1919

20-
| Name | Type | Description |
21-
| -------------------------------------- | ----------------------------------------------------- | ----------------------------- |
22-
| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory |
23-
| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map |
24-
| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity |
25-
| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration |
26-
| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects |
27-
| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud |
28-
| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states |
29-
| `~/input/virtual_traffic_light_states` | tier4_v2x_msgs::msg::VirtualTrafficLightStateArray | virtual traffic light states |
30-
| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid |
20+
| Name | Type | Description |
21+
| ------------------------------ | ----------------------------------------------------- | ----------------------------- |
22+
| `~/input/trajectory` | autoware_planning_msgs::msg::Trajectory | input trajectory |
23+
| `~/input/vector_map` | autoware_map_msgs::msg::LaneletMapBin | vector map |
24+
| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity |
25+
| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration |
26+
| `~/input/dynamic_objects` | autoware_perception_msgs::msg::PredictedObjects | dynamic objects |
27+
| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud |
28+
| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficLightGroupArray | traffic light states |
29+
| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid |
3130

3231
## Output topics
3332

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml

-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
<remap from="~/input/dynamic_objects" to="/perception/object_recognition/objects"/>
2525
<remap from="~/input/no_ground_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
2626
<remap from="~/input/traffic_signals" to="/perception/traffic_light_recognition/traffic_signals"/>
27-
<remap from="~/input/virtual_traffic_light_states" to="/perception/virtual_traffic_light_states"/>
2827
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
2928
<remap from="~/output/trajectory" to="trajectory"/>
3029
<!-- params -->

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

-3
Original file line numberDiff line numberDiff line change
@@ -185,9 +185,6 @@ bool MotionVelocityPlannerNode::update_planner_data(
185185
// optional data
186186
const auto traffic_signals_ptr = sub_traffic_signals_.takeData();
187187
if (traffic_signals_ptr) process_traffic_signals(traffic_signals_ptr);
188-
const auto virtual_traffic_light_states_ptr = sub_virtual_traffic_light_states_.takeData();
189-
if (virtual_traffic_light_states_ptr)
190-
planner_data_.virtual_traffic_light_states = *virtual_traffic_light_states_ptr;
191188
processing_times["update_planner_data.traffic_lights"] = sw.toc(true);
192189

193190
return is_ready;

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,6 @@ class MotionVelocityPlannerNode : public rclcpp::Node
8080
autoware::universe_utils::InterProcessPollingSubscriber<
8181
autoware_perception_msgs::msg::TrafficLightGroupArray>
8282
sub_traffic_signals_{this, "~/input/traffic_signals"};
83-
autoware::universe_utils::InterProcessPollingSubscriber<
84-
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>
85-
sub_virtual_traffic_light_states_{this, "~/input/virtual_traffic_light_states"};
8683
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapBin>::SharedPtr sub_lanelet_map_;
8784

8885
void on_trajectory(

‎planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -101,8 +101,6 @@ void publishMandatoryTopics(
101101
test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map");
102102
test_manager->publishTrafficSignals(
103103
test_target_node, "motion_velocity_planner_node/input/traffic_signals");
104-
test_manager->publishVirtualTrafficLightState(
105-
test_target_node, "motion_velocity_planner_node/input/virtual_traffic_light_states");
106104
test_manager->publishOccupancyGrid(
107105
test_target_node, "motion_velocity_planner_node/input/occupancy_grid");
108106
}

0 commit comments

Comments
 (0)
Please sign in to comment.