Skip to content

Commit

Permalink
feat(autoware_planning_test_manager): remove dependency of tier4_plan…
Browse files Browse the repository at this point in the history
…ning_msgs::msg::LateralOffset (#9967)

* feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset

Signed-off-by: Takayuki Murooka <[email protected]>

* fix

Signed-off-by: Takayuki Murooka <[email protected]>

---------

Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 authored Jan 19, 2025
1 parent 37fc242 commit 80eb07c
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 16 deletions.
2 changes: 0 additions & 2 deletions common/autoware_test_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,7 @@
<depend>std_srvs</depend>
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_api_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_v2x_msgs</depend>
<depend>unique_identifier_msgs</depend>
<depend>yaml_cpp_vendor</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/bool.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
#include <tier4_planning_msgs/msg/lateral_offset.hpp>
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
Expand Down Expand Up @@ -83,7 +82,6 @@ using nav_msgs::msg::OccupancyGrid;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tf2_msgs::msg::TFMessage;
using tier4_planning_msgs::msg::LateralOffset;
using tier4_planning_msgs::msg::PathWithLaneId;
using tier4_planning_msgs::msg::Scenario;
using tier4_planning_msgs::msg::VelocityLimit;
Expand Down Expand Up @@ -119,7 +117,6 @@ class PlanningInterfaceTestManager
void publishRoute(rclcpp::Node::SharedPtr target_node, std::string topic_name);
void publishTF(rclcpp::Node::SharedPtr target_node, std::string topic_name);
void publishInitialPoseTF(rclcpp::Node::SharedPtr target_node, std::string topic_name);
void publishLateralOffset(rclcpp::Node::SharedPtr target_node, std::string topic_name);
void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name);
void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name);

Expand Down Expand Up @@ -189,7 +186,6 @@ class PlanningInterfaceTestManager
rclcpp::Publisher<LaneletRoute>::SharedPtr route_pub_;
rclcpp::Publisher<TFMessage>::SharedPtr TF_pub_;
rclcpp::Publisher<TFMessage>::SharedPtr initial_pose_tf_pub_;
rclcpp::Publisher<LateralOffset>::SharedPtr lateral_offset_pub_;
rclcpp::Publisher<OperationModeState>::SharedPtr operation_mode_state_pub_;
rclcpp::Publisher<TrafficLightGroupArray>::SharedPtr traffic_signals_pub_;

Expand Down
1 change: 0 additions & 1 deletion planning/autoware_planning_test_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_v2x_msgs</depend>
<depend>unique_identifier_msgs</depend>
<depend>yaml_cpp_vendor</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,13 +153,6 @@ void PlanningInterfaceTestManager::publishTF(
autoware::test_utils::makeTFMsg(target_node, "base_link", "map"));
}

void PlanningInterfaceTestManager::publishLateralOffset(
rclcpp::Node::SharedPtr target_node, std::string topic_name)
{
autoware::test_utils::publishToTargetNode(
test_node_, target_node, topic_name, lateral_offset_pub_, LateralOffset{});
}

void PlanningInterfaceTestManager::publishOperationModeState(
rclcpp::Node::SharedPtr target_node, std::string topic_name)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,30 @@
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>

#include <tier4_planning_msgs/msg/lateral_offset.hpp>

#include <memory>
#include <string>
#include <vector>

namespace autoware::behavior_path_planner
{
namespace
{
using tier4_planning_msgs::msg::LateralOffset;

void publishLateralOffset(
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
std::shared_ptr<BehaviorPathPlannerNode> test_target_node)
{
auto test_node = test_manager->getTestNode();
const auto pub_lateral_offset = test_manager->getTestNode()->create_publisher<LateralOffset>(
"behavior_path_planner/input/lateral_offset", 1);
pub_lateral_offset->publish(LateralOffset{});
autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3);
}
} // namespace

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
Expand Down Expand Up @@ -95,7 +113,6 @@ void publishMandatoryTopics(
test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map");
test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap");
test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state");
test_manager->publishLateralOffset(
test_target_node, "behavior_path_planner/input/lateral_offset");
publishLateralOffset(test_manager, test_target_node);
}
} // namespace autoware::behavior_path_planner

0 comments on commit 80eb07c

Please sign in to comment.