Skip to content

Commit

Permalink
chore(planning): move package directory for planning factor interface (
Browse files Browse the repository at this point in the history
…#9948)

* chore: add new package for planning factor interface

Signed-off-by: satoshi-ota <[email protected]>

* chore(surround_obstacle_checker): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_stop_planner): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_cruise_planner): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(motion_velocity_planner): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(bpp): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(bvp-common): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(blind_spot): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(crosswalk): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(detection_area): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(intersection): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(no_drivable_area): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(no_stopping_area): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(occlusion_spot): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(run_out): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(speed_bump): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(stop_line): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(template_module): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(traffic_light): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(vtl): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(walkway): update include file

Signed-off-by: satoshi-ota <[email protected]>

* chore(motion_utils): remove factor interface

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Jan 17, 2025
1 parent 2a6663b commit aa95f2a
Show file tree
Hide file tree
Showing 62 changed files with 170 additions and 281 deletions.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_

#include "autoware/motion_utils/factor/planning_factor_interface.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/obstacle_cruise_planner/common_structs.hpp"
#include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp"
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
#include "autoware/obstacle_cruise_planner/utils.hpp"
#include "autoware/planning_factor_interface/planning_factor_interface.hpp"
#include "autoware/universe_utils/ros/update_param.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"

Expand Down Expand Up @@ -48,7 +48,8 @@ class PlannerInterface
rclcpp::Node & node, const LongitudinalInfo & longitudinal_info,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const EgoNearestParam & ego_nearest_param, const std::shared_ptr<DebugData> debug_data_ptr)
: planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>(
: planning_factor_interface_{std::make_unique<
autoware::planning_factor_interface::PlanningFactorInterface>(
&node, "obstacle_cruise_planner")},
longitudinal_info_(longitudinal_info),
vehicle_info_(vehicle_info),
Expand Down Expand Up @@ -130,7 +131,8 @@ class PlannerInterface
double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; }

protected:
std::unique_ptr<autoware::motion_utils::PlanningFactorInterface> planning_factor_interface_;
std::unique_ptr<autoware::planning_factor_interface::PlanningFactorInterface>
planning_factor_interface_;

// Parameters
bool enable_debug_info_{false};
Expand Down
1 change: 1 addition & 0 deletions planning/autoware_obstacle_cruise_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>autoware_objects_of_interest_marker_interface</depend>
<depend>autoware_osqp_interface</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_factor_interface</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_planning_test_manager</depend>
<depend>autoware_signal_processing</depend>
Expand Down
1 change: 1 addition & 0 deletions planning/autoware_obstacle_stop_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_factor_interface</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_planning_test_manager</depend>
<depend>autoware_signal_processing</depend>
Expand Down
5 changes: 3 additions & 2 deletions planning/autoware_obstacle_stop_planner/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,9 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode(
rclcpp::Node * node, const double base_link2front)
: node_(node),
base_link2front_(base_link2front),
planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>(
node, "obstacle_stop_planner")}
planning_factor_interface_{
std::make_unique<autoware::planning_factor_interface::PlanningFactorInterface>(
node, "obstacle_stop_planner")}
{
virtual_wall_pub_ = node_->create_publisher<MarkerArray>("~/virtual_wall", 1);
debug_viz_pub_ = node_->create_publisher<MarkerArray>("~/debug/marker", 1);
Expand Down
5 changes: 3 additions & 2 deletions planning/autoware_obstacle_stop_planner/src/debug_marker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#ifndef DEBUG_MARKER_HPP_
#define DEBUG_MARKER_HPP_

#include <autoware/motion_utils/factor/planning_factor_interface.hpp>
#include <autoware/planning_factor_interface/planning_factor_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/point.hpp>
Expand Down Expand Up @@ -119,7 +119,8 @@ class ObstacleStopPlannerDebugNode
rclcpp::Node * node_;
double base_link2front_;

std::unique_ptr<autoware::motion_utils::PlanningFactorInterface> planning_factor_interface_;
std::unique_ptr<autoware::planning_factor_interface::PlanningFactorInterface>
planning_factor_interface_;

std::shared_ptr<Pose> stop_pose_ptr_;
std::shared_ptr<Pose> target_stop_pose_ptr_;
Expand Down
11 changes: 11 additions & 0 deletions planning/autoware_planning_factor_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_planning_factor_interface)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(autoware_planning_factor_interface SHARED
DIRECTORY src
)

ament_auto_package()
1 change: 1 addition & 0 deletions planning/autoware_planning_factor_interface/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
# planning factor interface
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_
#define AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_
#ifndef AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_
#define AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_

#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -30,7 +30,7 @@
#include <string>
#include <vector>

namespace autoware::motion_utils
namespace autoware::planning_factor_interface
{

using geometry_msgs::msg::Pose;
Expand Down Expand Up @@ -235,6 +235,6 @@ extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::T
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);

} // namespace autoware::motion_utils
} // namespace autoware::planning_factor_interface

#endif // AUTOWARE__MOTION_UTILS__FACTOR__PLANNING_FACTOR_INTERFACE_HPP_
#endif // AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_
29 changes: 29 additions & 0 deletions planning/autoware_planning_factor_interface/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autoware_planning_factor_interface</name>
<version>0.40.0</version>
<description>The autoware_planning_factor_interface package</description>
<maintainer email="[email protected]">Satoshi Ota</maintainer>
<maintainer email="[email protected]">Mamoru Sobue</maintainer>
<license>Apache License 2.0</license>

<author email="[email protected]">Satoshi Ota</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>rclcpp</depend>
<depend>tier4_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <autoware/motion_utils/factor/planning_factor_interface.hpp>
#include <autoware/planning_factor_interface/planning_factor_interface.hpp>

#include <string>
#include <vector>

namespace autoware::motion_utils
namespace autoware::planning_factor_interface
{
template void PlanningFactorInterface::add<tier4_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<tier4_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
Expand All @@ -44,4 +44,4 @@ template void PlanningFactorInterface::add<autoware_planning_msgs::msg::Trajecto
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
} // namespace autoware::motion_utils
} // namespace autoware::planning_factor_interface
1 change: 1 addition & 0 deletions planning/autoware_surround_obstacle_checker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_factor_interface</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_planning_test_manager</depend>
<depend>autoware_universe_utils</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,8 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode(
const double & surround_check_back_distance, const double & surround_check_hysteresis_distance,
const geometry_msgs::msg::Pose & self_pose, const rclcpp::Clock::SharedPtr clock,
rclcpp::Node & node)
: planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>(
: planning_factor_interface_{std::make_unique<
autoware::planning_factor_interface::PlanningFactorInterface>(
&node, "surround_obstacle_checker")},
vehicle_info_(vehicle_info),
object_label_(object_label),
Expand Down
Loading

0 comments on commit aa95f2a

Please sign in to comment.