Skip to content

Commit 5c4fe25

Browse files
authored
fix(obstacle_cruise_planner): use planning factor interface (#1718)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 6be5ce0 commit 5c4fe25

File tree

4 files changed

+23
-1
lines changed

4 files changed

+23
-1
lines changed

planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
1616
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
1717

18+
#include "autoware/motion_utils/factor/planning_factor_interface.hpp"
1819
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1920
#include "autoware/obstacle_cruise_planner/common_structs.hpp"
2021
#include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp"
@@ -47,7 +48,9 @@ class PlannerInterface
4748
rclcpp::Node & node, const LongitudinalInfo & longitudinal_info,
4849
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
4950
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),
5154
vehicle_info_(vehicle_info),
5255
ego_nearest_param_(ego_nearest_param),
5356
debug_data_ptr_(debug_data_ptr),
@@ -101,6 +104,7 @@ class PlannerInterface
101104
const std::optional<geometry_msgs::msg::Pose> & stop_pose = std::nullopt,
102105
const std::optional<StopObstacle> & stop_obstacle = std::nullopt);
103106
void publishMetrics(const rclcpp::Time & current_time);
107+
void publishPlanningFactors() { planning_factor_interface_->publish(); }
104108
void clearMetrics();
105109

106110
void onParam(const std::vector<rclcpp::Parameter> & parameters)
@@ -128,6 +132,8 @@ class PlannerInterface
128132
double getSafeDistanceMargin() const { return longitudinal_info_.safe_distance_margin; }
129133

130134
protected:
135+
std::unique_ptr<autoware::motion_utils::PlanningFactorInterface> planning_factor_interface_;
136+
131137
// Parameters
132138
bool enable_debug_info_{false};
133139
bool enable_calculation_time_info_{false};

planning/autoware_obstacle_cruise_planner/src/node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -726,6 +726,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
726726
// 8. Publish debug data
727727
published_time_publisher_->publish_if_subscribed(trajectory_pub_, output_traj.header.stamp);
728728
planner_ptr_->publishMetrics(now());
729+
planner_ptr_->publishPlanningFactors();
729730
publishDebugMarker();
730731
publishDebugInfo();
731732
objects_of_interest_marker_interface_.publishMarkerArray();

planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -335,6 +335,10 @@ std::vector<TrajectoryPoint> PIDBasedPlanner::planCruise(
335335
debug_data_ptr_->obstacles_to_cruise.push_back(cruise_obstacle_info->obstacle);
336336
debug_data_ptr_->cruise_metrics = makeMetrics("PIDBasedPlanner", "cruise", planner_data);
337337

338+
planning_factor_interface_->add(
339+
stop_traj_points, planner_data.ego_pose, stop_traj_points.at(wall_idx).pose,
340+
tier4_planning_msgs::msg::PlanningFactor::NONE,
341+
tier4_planning_msgs::msg::SafetyFactorArray{});
338342
velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray(
339343
planner_data.current_time, PlanningBehavior::ADAPTIVE_CRUISE,
340344
stop_traj_points.at(wall_idx).pose));

planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -338,6 +338,10 @@ std::vector<TrajectoryPoint> PlannerInterface::generateStopTrajectory(
338338
const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose;
339339
velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray(
340340
planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, stop_pose));
341+
planning_factor_interface_->add(
342+
output_traj_points, planner_data.ego_pose, stop_pose,
343+
tier4_planning_msgs::msg::PlanningFactor::STOP,
344+
tier4_planning_msgs::msg::SafetyFactorArray{});
341345
// Store stop reason debug data
342346
debug_data_ptr_->stop_metrics =
343347
makeMetrics("PlannerInterface", "stop", planner_data, stop_pose, *determined_stop_obstacle);
@@ -594,6 +598,13 @@ std::vector<TrajectoryPoint> PlannerInterface::generateSlowDownTrajectory(
594598
planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE,
595599
slow_down_traj_points.at(slow_down_wall_idx).pose));
596600
autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker);
601+
planning_factor_interface_->add(
602+
slow_down_traj_points, planner_data.ego_pose,
603+
slow_down_traj_points.at(*slow_down_start_idx).pose,
604+
slow_down_traj_points.at(*slow_down_end_idx).pose,
605+
tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
606+
tier4_planning_msgs::msg::SafetyFactorArray{}, planner_data.is_driving_forward,
607+
stable_slow_down_vel);
597608
}
598609

599610
// add debug virtual wall

0 commit comments

Comments
 (0)