|
15 | 15 | #ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
|
16 | 16 | #define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
|
17 | 17 |
|
| 18 | +#include "autoware/motion_utils/factor/planning_factor_interface.hpp" |
18 | 19 | #include "autoware/motion_utils/trajectory/trajectory.hpp"
|
19 | 20 | #include "autoware/obstacle_cruise_planner/common_structs.hpp"
|
20 | 21 | #include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp"
|
@@ -47,7 +48,9 @@ class PlannerInterface
|
47 | 48 | rclcpp::Node & node, const LongitudinalInfo & longitudinal_info,
|
48 | 49 | const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
|
49 | 50 | const EgoNearestParam & ego_nearest_param, const std::shared_ptr<DebugData> debug_data_ptr)
|
50 |
| - : longitudinal_info_(longitudinal_info), |
| 51 | + : planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>( |
| 52 | + &node, "obstacle_cruise_planner")}, |
| 53 | + longitudinal_info_(longitudinal_info), |
51 | 54 | vehicle_info_(vehicle_info),
|
52 | 55 | ego_nearest_param_(ego_nearest_param),
|
53 | 56 | debug_data_ptr_(debug_data_ptr),
|
@@ -101,6 +104,7 @@ class PlannerInterface
|
101 | 104 | const std::optional<geometry_msgs::msg::Pose> & stop_pose = std::nullopt,
|
102 | 105 | const std::optional<StopObstacle> & stop_obstacle = std::nullopt);
|
103 | 106 | void publishMetrics(const rclcpp::Time & current_time);
|
| 107 | + void publishPlanningFactors() { planning_factor_interface_->publish(); } |
104 | 108 | void clearMetrics();
|
105 | 109 |
|
106 | 110 | void onParam(const std::vector<rclcpp::Parameter> & parameters)
|
@@ -128,6 +132,8 @@ class PlannerInterface
|
128 | 132 | double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; }
|
129 | 133 |
|
130 | 134 | protected:
|
| 135 | + std::unique_ptr<autoware::motion_utils::PlanningFactorInterface> planning_factor_interface_; |
| 136 | + |
131 | 137 | // Parameters
|
132 | 138 | bool enable_debug_info_{false};
|
133 | 139 | bool enable_calculation_time_info_{false};
|
|
0 commit comments