Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_planning_test_manager): remove dependency of tier4_planning_msgs::msg::LateralOffset #9967

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 45.05% to 44.94%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.

Check notice on line 1 in planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: String Heavy Function Arguments

The ratio of strings in function arguments decreases from 42.86% to 42.70%, threshold = 39.0%. The functions in this file have a high ratio of strings as arguments. Avoid adding more.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -153,13 +153,6 @@
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
Loading