52
52
#include < sensor_msgs/msg/point_cloud2.hpp>
53
53
#include < std_msgs/msg/bool.hpp>
54
54
#include < tf2_msgs/msg/tf_message.hpp>
55
- #include < tier4_api_msgs/msg/crosswalk_status.hpp>
56
- #include < tier4_api_msgs/msg/intersection_status.hpp>
57
- #include < tier4_planning_msgs/msg/expand_stop_range.hpp>
58
55
#include < tier4_planning_msgs/msg/lateral_offset.hpp>
59
56
#include < tier4_planning_msgs/msg/path_with_lane_id.hpp>
60
57
#include < tier4_planning_msgs/msg/scenario.hpp>
61
58
#include < tier4_planning_msgs/msg/velocity_limit.hpp>
62
- #include < tier4_v2x_msgs/msg/virtual_traffic_light_state_array.hpp>
63
59
64
60
#include < gtest/gtest.h>
65
61
#include < tf2_ros/buffer.h>
@@ -87,14 +83,10 @@ using nav_msgs::msg::OccupancyGrid;
87
83
using nav_msgs::msg::Odometry;
88
84
using sensor_msgs::msg::PointCloud2;
89
85
using tf2_msgs::msg::TFMessage;
90
- using tier4_api_msgs::msg::CrosswalkStatus;
91
- using tier4_api_msgs::msg::IntersectionStatus;
92
- using tier4_planning_msgs::msg::ExpandStopRange;
93
86
using tier4_planning_msgs::msg::LateralOffset;
94
87
using tier4_planning_msgs::msg::PathWithLaneId;
95
88
using tier4_planning_msgs::msg::Scenario;
96
89
using tier4_planning_msgs::msg::VelocityLimit;
97
- using tier4_v2x_msgs::msg::VirtualTrafficLightStateArray;
98
90
99
91
enum class ModuleName {
100
92
UNKNOWN = 0 ,
@@ -117,7 +109,6 @@ class PlanningInterfaceTestManager
117
109
void publishPointCloud (rclcpp::Node::SharedPtr target_node, std::string topic_name);
118
110
void publishAcceleration (rclcpp::Node::SharedPtr target_node, std::string topic_name);
119
111
void publishPredictedObjects (rclcpp::Node::SharedPtr target_node, std::string topic_name);
120
- void publishExpandStopRange (rclcpp::Node::SharedPtr target_node, std::string topic_name);
121
112
void publishOccupancyGrid (rclcpp::Node::SharedPtr target_node, std::string topic_name);
122
113
void publishCostMap (rclcpp::Node::SharedPtr target_node, std::string topic_name);
123
114
void publishMap (rclcpp::Node::SharedPtr target_node, std::string topic_name);
@@ -131,7 +122,6 @@ class PlanningInterfaceTestManager
131
122
void publishLateralOffset (rclcpp::Node::SharedPtr target_node, std::string topic_name);
132
123
void publishOperationModeState (rclcpp::Node::SharedPtr target_node, std::string topic_name);
133
124
void publishTrafficSignals (rclcpp::Node::SharedPtr target_node, std::string topic_name);
134
- void publishVirtualTrafficLightState (rclcpp::Node::SharedPtr target_node, std::string topic_name);
135
125
136
126
void setTrajectoryInputTopicName (std::string topic_name);
137
127
void setParkingTrajectoryInputTopicName (std::string topic_name);
@@ -178,6 +168,7 @@ class PlanningInterfaceTestManager
178
168
void testOffTrackFromTrajectory (rclcpp::Node::SharedPtr target_node);
179
169
180
170
int getReceivedTopicNum ();
171
+ rclcpp::Node::SharedPtr getTestNode () const ;
181
172
182
173
private:
183
174
// Publisher (necessary for node running)
@@ -187,7 +178,6 @@ class PlanningInterfaceTestManager
187
178
rclcpp::Publisher<PointCloud2>::SharedPtr point_cloud_pub_;
188
179
rclcpp::Publisher<AccelWithCovarianceStamped>::SharedPtr acceleration_pub_;
189
180
rclcpp::Publisher<PredictedObjects>::SharedPtr predicted_objects_pub_;
190
- rclcpp::Publisher<ExpandStopRange>::SharedPtr expand_stop_range_pub_;
191
181
rclcpp::Publisher<OccupancyGrid>::SharedPtr occupancy_grid_pub_;
192
182
rclcpp::Publisher<OccupancyGrid>::SharedPtr cost_map_pub_;
193
183
rclcpp::Publisher<LaneletMapBin>::SharedPtr map_pub_;
@@ -202,7 +192,6 @@ class PlanningInterfaceTestManager
202
192
rclcpp::Publisher<LateralOffset>::SharedPtr lateral_offset_pub_;
203
193
rclcpp::Publisher<OperationModeState>::SharedPtr operation_mode_state_pub_;
204
194
rclcpp::Publisher<TrafficLightGroupArray>::SharedPtr traffic_signals_pub_;
205
- rclcpp::Publisher<VirtualTrafficLightStateArray>::SharedPtr virtual_traffic_light_states_pub_;
206
195
207
196
// Subscriber
208
197
rclcpp::Subscription<Trajectory>::SharedPtr traj_sub_;
0 commit comments