Skip to content

Commit 4b16661

Browse files
authored
feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (#9953)
* feat(autoware_planning_test_manager): remove dependency of virtual traffic light Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * modify obstacle_stop test code Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 64e4e21 commit 4b16661

File tree

5 files changed

+41
-34
lines changed

5 files changed

+41
-34
lines changed

planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp

+16-2
Original file line numberDiff line numberDiff line change
@@ -18,13 +18,16 @@
1818
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
1919
#include <autoware_test_utils/autoware_test_utils.hpp>
2020

21+
#include <tier4_planning_msgs/msg/expand_stop_range.hpp>
22+
2123
#include <gtest/gtest.h>
2224

2325
#include <memory>
2426
#include <vector>
2527

2628
using autoware::motion_planning::ObstacleStopPlannerNode;
2729
using autoware::planning_test_manager::PlanningInterfaceTestManager;
30+
using tier4_planning_msgs::msg::ExpandStopRange;
2831

2932
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
3033
{
@@ -66,8 +69,17 @@ void publishMandatoryTopics(
6669
test_manager->publishPointCloud(test_target_node, "obstacle_stop_planner/input/pointcloud");
6770
test_manager->publishAcceleration(test_target_node, "obstacle_stop_planner/input/acceleration");
6871
test_manager->publishPredictedObjects(test_target_node, "obstacle_stop_planner/input/objects");
69-
test_manager->publishExpandStopRange(
70-
test_target_node, "obstacle_stop_planner/input/expand_stop_range");
72+
}
73+
74+
void publishExpandStopRange(
75+
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
76+
std::shared_ptr<ObstacleStopPlannerNode> test_target_node)
77+
{
78+
auto test_node = test_manager->getTestNode();
79+
const auto expand_stop_range = test_manager->getTestNode()->create_publisher<ExpandStopRange>(
80+
"obstacle_stop_planner/input/expand_stop_range", 1);
81+
expand_stop_range->publish(ExpandStopRange{});
82+
autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3);
7183
}
7284

7385
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
@@ -78,6 +90,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
7890
auto test_target_node = generateNode();
7991

8092
publishMandatoryTopics(test_manager, test_target_node);
93+
publishExpandStopRange(test_manager, test_target_node);
8194

8295
// test for normal trajectory
8396
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node));
@@ -97,6 +110,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
97110
auto test_target_node = generateNode();
98111

99112
publishMandatoryTopics(test_manager, test_target_node);
113+
publishExpandStopRange(test_manager, test_target_node);
100114

101115
// test for normal trajectory
102116
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node));

planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp

+1-12
Original file line numberDiff line numberDiff line change
@@ -52,14 +52,10 @@
5252
#include <sensor_msgs/msg/point_cloud2.hpp>
5353
#include <std_msgs/msg/bool.hpp>
5454
#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>
5855
#include <tier4_planning_msgs/msg/lateral_offset.hpp>
5956
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
6057
#include <tier4_planning_msgs/msg/scenario.hpp>
6158
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
62-
#include <tier4_v2x_msgs/msg/virtual_traffic_light_state_array.hpp>
6359

6460
#include <gtest/gtest.h>
6561
#include <tf2_ros/buffer.h>
@@ -87,14 +83,10 @@ using nav_msgs::msg::OccupancyGrid;
8783
using nav_msgs::msg::Odometry;
8884
using sensor_msgs::msg::PointCloud2;
8985
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;
9386
using tier4_planning_msgs::msg::LateralOffset;
9487
using tier4_planning_msgs::msg::PathWithLaneId;
9588
using tier4_planning_msgs::msg::Scenario;
9689
using tier4_planning_msgs::msg::VelocityLimit;
97-
using tier4_v2x_msgs::msg::VirtualTrafficLightStateArray;
9890

9991
enum class ModuleName {
10092
UNKNOWN = 0,
@@ -117,7 +109,6 @@ class PlanningInterfaceTestManager
117109
void publishPointCloud(rclcpp::Node::SharedPtr target_node, std::string topic_name);
118110
void publishAcceleration(rclcpp::Node::SharedPtr target_node, std::string topic_name);
119111
void publishPredictedObjects(rclcpp::Node::SharedPtr target_node, std::string topic_name);
120-
void publishExpandStopRange(rclcpp::Node::SharedPtr target_node, std::string topic_name);
121112
void publishOccupancyGrid(rclcpp::Node::SharedPtr target_node, std::string topic_name);
122113
void publishCostMap(rclcpp::Node::SharedPtr target_node, std::string topic_name);
123114
void publishMap(rclcpp::Node::SharedPtr target_node, std::string topic_name);
@@ -131,7 +122,6 @@ class PlanningInterfaceTestManager
131122
void publishLateralOffset(rclcpp::Node::SharedPtr target_node, std::string topic_name);
132123
void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name);
133124
void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name);
134-
void publishVirtualTrafficLightState(rclcpp::Node::SharedPtr target_node, std::string topic_name);
135125

136126
void setTrajectoryInputTopicName(std::string topic_name);
137127
void setParkingTrajectoryInputTopicName(std::string topic_name);
@@ -178,6 +168,7 @@ class PlanningInterfaceTestManager
178168
void testOffTrackFromTrajectory(rclcpp::Node::SharedPtr target_node);
179169

180170
int getReceivedTopicNum();
171+
rclcpp::Node::SharedPtr getTestNode() const;
181172

182173
private:
183174
// Publisher (necessary for node running)
@@ -187,7 +178,6 @@ class PlanningInterfaceTestManager
187178
rclcpp::Publisher<PointCloud2>::SharedPtr point_cloud_pub_;
188179
rclcpp::Publisher<AccelWithCovarianceStamped>::SharedPtr acceleration_pub_;
189180
rclcpp::Publisher<PredictedObjects>::SharedPtr predicted_objects_pub_;
190-
rclcpp::Publisher<ExpandStopRange>::SharedPtr expand_stop_range_pub_;
191181
rclcpp::Publisher<OccupancyGrid>::SharedPtr occupancy_grid_pub_;
192182
rclcpp::Publisher<OccupancyGrid>::SharedPtr cost_map_pub_;
193183
rclcpp::Publisher<LaneletMapBin>::SharedPtr map_pub_;
@@ -202,7 +192,6 @@ class PlanningInterfaceTestManager
202192
rclcpp::Publisher<LateralOffset>::SharedPtr lateral_offset_pub_;
203193
rclcpp::Publisher<OperationModeState>::SharedPtr operation_mode_state_pub_;
204194
rclcpp::Publisher<TrafficLightGroupArray>::SharedPtr traffic_signals_pub_;
205-
rclcpp::Publisher<VirtualTrafficLightStateArray>::SharedPtr virtual_traffic_light_states_pub_;
206195

207196
// Subscriber
208197
rclcpp::Subscription<Trajectory>::SharedPtr traj_sub_;

planning/autoware_planning_test_manager/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,6 @@
3131
<depend>rclcpp</depend>
3232
<depend>tf2_msgs</depend>
3333
<depend>tf2_ros</depend>
34-
<depend>tier4_api_msgs</depend>
3534
<depend>tier4_planning_msgs</depend>
3635
<depend>tier4_v2x_msgs</depend>
3736
<depend>unique_identifier_msgs</depend>

planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

+5-15
Original file line numberDiff line numberDiff line change
@@ -71,13 +71,6 @@ void PlanningInterfaceTestManager::publishPredictedObjects(
7171
test_node_, target_node, topic_name, predicted_objects_pub_, PredictedObjects{});
7272
}
7373

74-
void PlanningInterfaceTestManager::publishExpandStopRange(
75-
rclcpp::Node::SharedPtr target_node, std::string topic_name)
76-
{
77-
autoware::test_utils::publishToTargetNode(
78-
test_node_, target_node, topic_name, expand_stop_range_pub_, ExpandStopRange{});
79-
}
80-
8174
void PlanningInterfaceTestManager::publishOccupancyGrid(
8275
rclcpp::Node::SharedPtr target_node, std::string topic_name)
8376
{
@@ -181,14 +174,6 @@ void PlanningInterfaceTestManager::publishTrafficSignals(
181174
test_node_, target_node, topic_name, traffic_signals_pub_, TrafficLightGroupArray{});
182175
}
183176

184-
void PlanningInterfaceTestManager::publishVirtualTrafficLightState(
185-
rclcpp::Node::SharedPtr target_node, std::string topic_name)
186-
{
187-
autoware::test_utils::publishToTargetNode(
188-
test_node_, target_node, topic_name, virtual_traffic_light_states_pub_,
189-
VirtualTrafficLightStateArray{});
190-
}
191-
192177
void PlanningInterfaceTestManager::publishInitialPoseTF(
193178
rclcpp::Node::SharedPtr target_node, std::string topic_name)
194179
{
@@ -471,4 +456,9 @@ int PlanningInterfaceTestManager::getReceivedTopicNum()
471456
return count_;
472457
}
473458

459+
rclcpp::Node::SharedPtr PlanningInterfaceTestManager::getTestNode() const
460+
{
461+
return test_node_;
462+
}
463+
474464
} // namespace autoware::planning_test_manager

planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp

+19-4
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,9 @@
1313
// limitations under the License.
1414

1515
#include <autoware/behavior_velocity_planner/test_utils.hpp>
16+
#include <autoware_test_utils/autoware_test_utils.hpp>
17+
18+
#include <tier4_v2x_msgs/msg/virtual_traffic_light_state_array.hpp>
1619

1720
#include <gtest/gtest.h>
1821

@@ -23,6 +26,19 @@
2326

2427
namespace autoware::behavior_velocity_planner
2528
{
29+
using tier4_v2x_msgs::msg::VirtualTrafficLightStateArray;
30+
31+
void publishVirtualTrafficLightState(
32+
std::shared_ptr<PlanningInterfaceTestManager> test_manager, rclcpp::Node::SharedPtr target_node)
33+
{
34+
auto test_node = test_manager->getTestNode();
35+
const auto pub_virtual_traffic_light =
36+
test_manager->getTestNode()->create_publisher<VirtualTrafficLightStateArray>(
37+
"behavior_velocity_planner_node/input/virtual_traffic_light_states", 1);
38+
pub_virtual_traffic_light->publish(VirtualTrafficLightStateArray{});
39+
autoware::test_utils::spinSomeNodes(test_node, target_node, 3);
40+
}
41+
2642
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
2743
{
2844
rclcpp::init(0, nullptr);
@@ -35,8 +51,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
3551
auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec);
3652

3753
autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node);
38-
test_manager->publishVirtualTrafficLightState(
39-
test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states");
54+
publishVirtualTrafficLightState(test_manager, test_target_node);
4055

4156
// test with nominal path_with_lane_id
4257
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
@@ -57,9 +72,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
5772

5873
auto test_manager = autoware::behavior_velocity_planner::generateTestManager();
5974
auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec);
75+
6076
autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node);
61-
test_manager->publishVirtualTrafficLightState(
62-
test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states");
77+
publishVirtualTrafficLightState(test_manager, test_target_node);
6378

6479
// test for normal trajectory
6580
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));

0 commit comments

Comments
 (0)