Skip to content

Commit 6f40830

Browse files
authored
refactor(factor): move steering factor interface to motion utils (#9337)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 08951b2 commit 6f40830

File tree

6 files changed

+16
-22
lines changed

6 files changed

+16
-22
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2022 Tier IV, Inc.
1+
// Copyright 2022 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,19 +12,16 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_
16-
#define AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_
17-
18-
#include <rclcpp/rclcpp.hpp>
15+
#ifndef AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_
16+
#define AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_
1917

2018
#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
2119
#include <autoware_adapi_v1_msgs/msg/steering_factor.hpp>
2220
#include <geometry_msgs/msg/pose.hpp>
2321

24-
#include <mutex>
2522
#include <string>
2623

27-
namespace steering_factor_interface
24+
namespace autoware::motion_utils
2825
{
2926

3027
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
@@ -49,6 +46,6 @@ class SteeringFactorInterface
4946
SteeringFactor steering_factor_{};
5047
};
5148

52-
} // namespace steering_factor_interface
49+
} // namespace autoware::motion_utils
5350

54-
#endif // AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_
51+
#endif // AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2022 Tier IV, Inc.
1+
// Copyright 2022 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,9 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp"
15+
#include <autoware/motion_utils/factor/steering_factor_interface.hpp>
1616

17-
namespace steering_factor_interface
17+
namespace autoware::motion_utils
1818
{
1919
void SteeringFactorInterface::set(
2020
const std::array<Pose, 2> & pose, const std::array<double, 2> distance, const uint16_t direction,
@@ -29,4 +29,4 @@ void SteeringFactorInterface::set(
2929
steering_factor_.status = status;
3030
steering_factor_.detail = detail;
3131
}
32-
} // namespace steering_factor_interface
32+
} // namespace autoware::motion_utils

planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,10 @@
1717

1818
#include "autoware/behavior_path_planner_common/data_manager.hpp"
1919
#include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp"
20-
#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp"
2120
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
2221
#include "planner_manager.hpp"
2322

23+
#include <autoware/motion_utils/factor/steering_factor_interface.hpp>
2424
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
2525
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
2626

@@ -52,6 +52,7 @@
5252

5353
namespace autoware::behavior_path_planner
5454
{
55+
using autoware::motion_utils::SteeringFactorInterface;
5556
using autoware_adapi_v1_msgs::msg::OperationModeState;
5657
using autoware_map_msgs::msg::LaneletMapBin;
5758
using autoware_perception_msgs::msg::PredictedObject;
@@ -65,7 +66,6 @@ using autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
6566
using nav_msgs::msg::OccupancyGrid;
6667
using nav_msgs::msg::Odometry;
6768
using rcl_interfaces::msg::SetParametersResult;
68-
using steering_factor_interface::SteeringFactorInterface;
6969
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
7070
using tier4_planning_msgs::msg::LateralOffset;
7171
using tier4_planning_msgs::msg::PathWithLaneId;

planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt

-1
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,6 @@ find_package(magic_enum CONFIG REQUIRED)
88

99
ament_auto_add_library(${PROJECT_NAME} SHARED
1010
src/turn_signal_decider.cpp
11-
src/interface/steering_factor_interface.cpp
1211
src/interface/scene_module_visitor.cpp
1312
src/interface/scene_module_interface.cpp
1413
src/interface/scene_module_manager_interface.cpp

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@
2020
#include "autoware/behavior_path_planner_common/marker_utils/utils.hpp"
2121
#include "autoware/behavior_path_planner_common/utils/utils.hpp"
2222

23-
#include <autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp>
2423
#include <autoware/behavior_path_planner_common/turn_signal_decider.hpp>
24+
#include <autoware/motion_utils/factor/steering_factor_interface.hpp>
2525
#include <autoware/motion_utils/marker/marker_helper.hpp>
2626
#include <autoware/motion_utils/trajectory/path_with_lane_id.hpp>
2727
#include <autoware/motion_utils/trajectory/trajectory.hpp>
@@ -35,8 +35,7 @@
3535
#include <magic_enum.hpp>
3636
#include <rclcpp/rclcpp.hpp>
3737

38-
#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
39-
#include <autoware_adapi_v1_msgs/msg/steering_factor_array.hpp>
38+
#include <autoware_adapi_v1_msgs/msg/steering_factor.hpp>
4039
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
4140
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
4241
#include <tier4_planning_msgs/msg/stop_factor.hpp>
@@ -57,14 +56,14 @@
5756

5857
namespace autoware::behavior_path_planner
5958
{
59+
using autoware::motion_utils::SteeringFactorInterface;
6060
using autoware::objects_of_interest_marker_interface::ColorName;
6161
using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface;
6262
using autoware::rtc_interface::RTCInterface;
6363
using autoware::universe_utils::calcOffsetPose;
6464
using autoware::universe_utils::generateUUID;
6565
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
6666
using autoware_adapi_v1_msgs::msg::SteeringFactor;
67-
using steering_factor_interface::SteeringFactorInterface;
6867
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
6968
using tier4_planning_msgs::msg::PathWithLaneId;
7069
using tier4_planning_msgs::msg::StopFactor;
@@ -74,7 +73,6 @@ using tier4_rtc_msgs::msg::State;
7473
using unique_identifier_msgs::msg::UUID;
7574
using visualization_msgs::msg::MarkerArray;
7675
using PlanResult = PathWithLaneId::SharedPtr;
77-
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
7876

7977
enum class ModuleStatus {
8078
IDLE = 0,

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ class SceneModuleManagerInterface
106106

107107
void publishSteeringFactor()
108108
{
109-
autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array;
109+
SteeringFactorArray steering_factor_array;
110110
steering_factor_array.header.frame_id = "map";
111111
steering_factor_array.header.stamp = node_->now();
112112

0 commit comments

Comments
 (0)