Skip to content

Commit

Permalink
refactor(factor): move steering factor interface to motion utils
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Nov 15, 2024
1 parent d819a66 commit 0c2d614
Show file tree
Hide file tree
Showing 6 changed files with 16 additions and 22 deletions.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 Tier IV, Inc.
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,19 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_
#define AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_

#include <rclcpp/rclcpp.hpp>
#ifndef AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_
#define AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/steering_factor.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <mutex>
#include <string>

namespace steering_factor_interface
namespace autoware::motion_utils
{

using autoware_adapi_v1_msgs::msg::PlanningBehavior;
Expand All @@ -49,6 +46,6 @@ class SteeringFactorInterface
SteeringFactor steering_factor_{};
};

} // namespace steering_factor_interface
} // namespace autoware::motion_utils

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

#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp"
#include <autoware/motion_utils/factor/steering_factor_interface.hpp>

namespace steering_factor_interface
namespace autoware::motion_utils
{
void SteeringFactorInterface::set(
const std::array<Pose, 2> & pose, const std::array<double, 2> distance, const uint16_t direction,
Expand All @@ -29,4 +29,4 @@ void SteeringFactorInterface::set(
steering_factor_.status = status;
steering_factor_.detail = detail;
}
} // namespace steering_factor_interface
} // namespace autoware::motion_utils
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

#include "autoware/behavior_path_planner_common/data_manager.hpp"
#include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp"
#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp"
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
#include "planner_manager.hpp"

#include <autoware/motion_utils/factor/steering_factor_interface.hpp>
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <autoware/universe_utils/ros/published_time_publisher.hpp>

Expand Down Expand Up @@ -52,6 +52,7 @@

namespace autoware::behavior_path_planner
{
using autoware::motion_utils::SteeringFactorInterface;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_map_msgs::msg::LaneletMapBin;
using autoware_perception_msgs::msg::PredictedObject;
Expand All @@ -65,7 +66,6 @@ using autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
using nav_msgs::msg::OccupancyGrid;
using nav_msgs::msg::Odometry;
using rcl_interfaces::msg::SetParametersResult;
using steering_factor_interface::SteeringFactorInterface;
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
using tier4_planning_msgs::msg::LateralOffset;
using tier4_planning_msgs::msg::PathWithLaneId;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@ find_package(magic_enum CONFIG REQUIRED)

ament_auto_add_library(${PROJECT_NAME} SHARED
src/turn_signal_decider.cpp
src/interface/steering_factor_interface.cpp
src/interface/scene_module_visitor.cpp
src/interface/scene_module_interface.cpp
src/interface/scene_module_manager_interface.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include "autoware/behavior_path_planner_common/marker_utils/utils.hpp"
#include "autoware/behavior_path_planner_common/utils/utils.hpp"

#include <autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp>
#include <autoware/behavior_path_planner_common/turn_signal_decider.hpp>
#include <autoware/motion_utils/factor/steering_factor_interface.hpp>
#include <autoware/motion_utils/marker/marker_helper.hpp>
#include <autoware/motion_utils/trajectory/path_with_lane_id.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
Expand All @@ -35,8 +35,7 @@
#include <magic_enum.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/steering_factor_array.hpp>
#include <autoware_adapi_v1_msgs/msg/steering_factor.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
#include <tier4_planning_msgs/msg/stop_factor.hpp>
Expand All @@ -57,14 +56,14 @@

namespace autoware::behavior_path_planner
{
using autoware::motion_utils::SteeringFactorInterface;
using autoware::objects_of_interest_marker_interface::ColorName;
using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface;
using autoware::rtc_interface::RTCInterface;
using autoware::universe_utils::calcOffsetPose;
using autoware::universe_utils::generateUUID;
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::SteeringFactor;
using steering_factor_interface::SteeringFactorInterface;
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
using tier4_planning_msgs::msg::PathWithLaneId;
using tier4_planning_msgs::msg::StopFactor;
Expand All @@ -74,7 +73,6 @@ using tier4_rtc_msgs::msg::State;
using unique_identifier_msgs::msg::UUID;
using visualization_msgs::msg::MarkerArray;
using PlanResult = PathWithLaneId::SharedPtr;
using autoware_adapi_v1_msgs::msg::PlanningBehavior;

enum class ModuleStatus {
IDLE = 0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ class SceneModuleManagerInterface

void publishSteeringFactor()
{
autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array;
SteeringFactorArray steering_factor_array;
steering_factor_array.header.frame_id = "map";
steering_factor_array.header.stamp = node_->now();

Expand Down

0 comments on commit 0c2d614

Please sign in to comment.