|
| 1 | +// Copyright 2025 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "autoware/planning_test_manager/autoware_planning_test_manager.hpp" |
| 16 | + |
| 17 | +#include <gtest/gtest.h> |
| 18 | + |
| 19 | +#include <memory> |
| 20 | + |
| 21 | +TEST(PlanningTestManager, CommunicationTest) |
| 22 | +{ |
| 23 | + using autoware_internal_planning_msgs::msg::PathWithLaneId; |
| 24 | + using autoware_planning_msgs::msg::LaneletRoute; |
| 25 | + using autoware_planning_msgs::msg::Path; |
| 26 | + using autoware_planning_msgs::msg::Trajectory; |
| 27 | + using nav_msgs::msg::Odometry; |
| 28 | + |
| 29 | + rclcpp::init(0, nullptr); |
| 30 | + |
| 31 | + // instantiate test_manager with PlanningInterfaceTestManager type |
| 32 | + auto test_manager = |
| 33 | + std::make_shared<autoware::planning_test_manager::PlanningInterfaceTestManager>(); |
| 34 | + |
| 35 | + // instantiate the TargetNode for test |
| 36 | + auto test_target_node = std::make_shared<rclcpp::Node>("target_node_for_test"); |
| 37 | + |
| 38 | + test_manager->resetReceivedTopicNum(); |
| 39 | + test_manager->subscribeOutput<Trajectory>("normal_trajectory_for_test"); |
| 40 | + test_manager->testWithNormalTrajectory(test_target_node, "normal_trajectory_for_test"); |
| 41 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 42 | + |
| 43 | + test_manager->resetReceivedTopicNum(); |
| 44 | + test_manager->subscribeOutput<Trajectory>("abnormal_trajectory_for_test"); |
| 45 | + test_manager->testWithAbnormalTrajectory(test_target_node, "abnormal_trajectory_for_test"); |
| 46 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 47 | + |
| 48 | + test_manager->resetReceivedTopicNum(); |
| 49 | + test_manager->subscribeOutput<LaneletRoute>("normal_route_for_test"); |
| 50 | + test_manager->testWithNormalRoute(test_target_node, "normal_route_for_test"); |
| 51 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 52 | + |
| 53 | + test_manager->resetReceivedTopicNum(); |
| 54 | + test_manager->subscribeOutput<LaneletRoute>("abnormal_route_for_test"); |
| 55 | + test_manager->testWithAbnormalRoute(test_target_node, "abnormal_route_for_test"); |
| 56 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 57 | + |
| 58 | + test_manager->resetReceivedTopicNum(); |
| 59 | + test_manager->subscribeOutput<LaneletRoute>("behavior_normal_route_for_test"); |
| 60 | + test_manager->testWithBehaviorNormalRoute(test_target_node, "behavior_normal_route_for_test"); |
| 61 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 62 | + |
| 63 | + test_manager->resetReceivedTopicNum(); |
| 64 | + test_manager->subscribeOutput<LaneletRoute>("behavior_goal_on_left_side_route_for_test"); |
| 65 | + test_manager->testWithBehaviorGoalOnLeftSide( |
| 66 | + test_target_node, "behavior_goal_on_left_side_route_for_test"); |
| 67 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 68 | + |
| 69 | + test_manager->resetReceivedTopicNum(); |
| 70 | + test_manager->subscribeOutput<PathWithLaneId>("normal_path_with_lane_id_for_test"); |
| 71 | + test_manager->testWithNormalPathWithLaneId(test_target_node, "normal_path_with_lane_id_for_test"); |
| 72 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 73 | + |
| 74 | + test_manager->resetReceivedTopicNum(); |
| 75 | + test_manager->subscribeOutput<PathWithLaneId>("abnormal_path_with_lane_id_for_test"); |
| 76 | + test_manager->testWithAbnormalPathWithLaneId( |
| 77 | + test_target_node, "abnormal_path_with_lane_id_for_test"); |
| 78 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 79 | + |
| 80 | + test_manager->resetReceivedTopicNum(); |
| 81 | + test_manager->subscribeOutput<Path>("normal_path_for_test"); |
| 82 | + test_manager->testWithNormalPath(test_target_node, "normal_path_for_test"); |
| 83 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 84 | + |
| 85 | + test_manager->resetReceivedTopicNum(); |
| 86 | + test_manager->subscribeOutput<Path>("abnormal_path_for_test"); |
| 87 | + test_manager->testWithAbnormalPath(test_target_node, "abnormal_path_for_test"); |
| 88 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 89 | + |
| 90 | + test_manager->resetReceivedTopicNum(); |
| 91 | + test_manager->subscribeOutput<Odometry>("off_track_initial_poses_for_test"); |
| 92 | + test_manager->testWithOffTrackInitialPoses(test_target_node, "off_track_initial_poses_for_test"); |
| 93 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 94 | + |
| 95 | + test_manager->resetReceivedTopicNum(); |
| 96 | + test_manager->subscribeOutput<Odometry>("off_track_odometry_for_test"); |
| 97 | + test_manager->testWithOffTrackOdometry(test_target_node, "off_track_odometry_for_test"); |
| 98 | + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); |
| 99 | + |
| 100 | + // shutdown ROS context |
| 101 | + rclcpp::shutdown(); |
| 102 | +} |
0 commit comments