Skip to content

Commit 80eb07c

Browse files
authored
feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset (#9967)
* feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset 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 37fc242 commit 80eb07c

File tree

5 files changed

+19
-16
lines changed

5 files changed

+19
-16
lines changed

common/autoware_test_utils/package.xml

-2
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,7 @@
3333
<depend>std_srvs</depend>
3434
<depend>tf2_msgs</depend>
3535
<depend>tf2_ros</depend>
36-
<depend>tier4_api_msgs</depend>
3736
<depend>tier4_planning_msgs</depend>
38-
<depend>tier4_v2x_msgs</depend>
3937
<depend>unique_identifier_msgs</depend>
4038
<depend>yaml_cpp_vendor</depend>
4139

planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,6 @@
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_planning_msgs/msg/lateral_offset.hpp>
5655
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
5756
#include <tier4_planning_msgs/msg/scenario.hpp>
5857
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
@@ -83,7 +82,6 @@ using nav_msgs::msg::OccupancyGrid;
8382
using nav_msgs::msg::Odometry;
8483
using sensor_msgs::msg::PointCloud2;
8584
using tf2_msgs::msg::TFMessage;
86-
using tier4_planning_msgs::msg::LateralOffset;
8785
using tier4_planning_msgs::msg::PathWithLaneId;
8886
using tier4_planning_msgs::msg::Scenario;
8987
using tier4_planning_msgs::msg::VelocityLimit;
@@ -119,7 +117,6 @@ class PlanningInterfaceTestManager
119117
void publishRoute(rclcpp::Node::SharedPtr target_node, std::string topic_name);
120118
void publishTF(rclcpp::Node::SharedPtr target_node, std::string topic_name);
121119
void publishInitialPoseTF(rclcpp::Node::SharedPtr target_node, std::string topic_name);
122-
void publishLateralOffset(rclcpp::Node::SharedPtr target_node, std::string topic_name);
123120
void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name);
124121
void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name);
125122

@@ -189,7 +186,6 @@ class PlanningInterfaceTestManager
189186
rclcpp::Publisher<LaneletRoute>::SharedPtr route_pub_;
190187
rclcpp::Publisher<TFMessage>::SharedPtr TF_pub_;
191188
rclcpp::Publisher<TFMessage>::SharedPtr initial_pose_tf_pub_;
192-
rclcpp::Publisher<LateralOffset>::SharedPtr lateral_offset_pub_;
193189
rclcpp::Publisher<OperationModeState>::SharedPtr operation_mode_state_pub_;
194190
rclcpp::Publisher<TrafficLightGroupArray>::SharedPtr traffic_signals_pub_;
195191

planning/autoware_planning_test_manager/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
<depend>tf2_msgs</depend>
3333
<depend>tf2_ros</depend>
3434
<depend>tier4_planning_msgs</depend>
35-
<depend>tier4_v2x_msgs</depend>
3635
<depend>unique_identifier_msgs</depend>
3736
<depend>yaml_cpp_vendor</depend>
3837

planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

-7
Original file line numberDiff line numberDiff line change
@@ -153,13 +153,6 @@ void PlanningInterfaceTestManager::publishTF(
153153
autoware::test_utils::makeTFMsg(target_node, "base_link", "map"));
154154
}
155155

156-
void PlanningInterfaceTestManager::publishLateralOffset(
157-
rclcpp::Node::SharedPtr target_node, std::string topic_name)
158-
{
159-
autoware::test_utils::publishToTargetNode(
160-
test_node_, target_node, topic_name, lateral_offset_pub_, LateralOffset{});
161-
}
162-
163156
void PlanningInterfaceTestManager::publishOperationModeState(
164157
rclcpp::Node::SharedPtr target_node, std::string topic_name)
165158
{

planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp

+19-2
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,30 @@
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/lateral_offset.hpp>
22+
2123
#include <memory>
2224
#include <string>
2325
#include <vector>
2426

2527
namespace autoware::behavior_path_planner
2628
{
29+
namespace
30+
{
31+
using tier4_planning_msgs::msg::LateralOffset;
32+
33+
void publishLateralOffset(
34+
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
35+
std::shared_ptr<BehaviorPathPlannerNode> test_target_node)
36+
{
37+
auto test_node = test_manager->getTestNode();
38+
const auto pub_lateral_offset = test_manager->getTestNode()->create_publisher<LateralOffset>(
39+
"behavior_path_planner/input/lateral_offset", 1);
40+
pub_lateral_offset->publish(LateralOffset{});
41+
autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3);
42+
}
43+
} // namespace
44+
2745
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
2846
{
2947
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
@@ -95,7 +113,6 @@ void publishMandatoryTopics(
95113
test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map");
96114
test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap");
97115
test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state");
98-
test_manager->publishLateralOffset(
99-
test_target_node, "behavior_path_planner/input/lateral_offset");
116+
publishLateralOffset(test_manager, test_target_node);
100117
}
101118
} // namespace autoware::behavior_path_planner

0 commit comments

Comments
 (0)