Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(obstacle_cruise_planner): use planning factor interface #1718

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#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"
Expand Down Expand Up @@ -47,7 +48,9 @@ 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)
: longitudinal_info_(longitudinal_info),
: planning_factor_interface_{std::make_unique<autoware::motion_utils::PlanningFactorInterface>(
&node, "obstacle_cruise_planner")},
longitudinal_info_(longitudinal_info),
vehicle_info_(vehicle_info),
ego_nearest_param_(ego_nearest_param),
debug_data_ptr_(debug_data_ptr),
Expand Down Expand Up @@ -101,6 +104,7 @@ class PlannerInterface
const std::optional<geometry_msgs::msg::Pose> & stop_pose = std::nullopt,
const std::optional<StopObstacle> & stop_obstacle = std::nullopt);
void publishMetrics(const rclcpp::Time & current_time);
void publishPlanningFactors() { planning_factor_interface_->publish(); }
void clearMetrics();

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

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

// Parameters
bool enable_debug_info_{false};
bool enable_calculation_time_info_{false};
Expand Down
1 change: 1 addition & 0 deletions planning/autoware_obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -726,6 +726,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
// 8. Publish debug data
published_time_publisher_->publish_if_subscribed(trajectory_pub_, output_traj.header.stamp);
planner_ptr_->publishMetrics(now());
planner_ptr_->publishPlanningFactors();
publishDebugMarker();
publishDebugInfo();
objects_of_interest_marker_interface_.publishMarkerArray();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -335,6 +335,10 @@ std::vector<TrajectoryPoint> PIDBasedPlanner::planCruise(
debug_data_ptr_->obstacles_to_cruise.push_back(cruise_obstacle_info->obstacle);
debug_data_ptr_->cruise_metrics = makeMetrics("PIDBasedPlanner", "cruise", planner_data);

planning_factor_interface_->add(
stop_traj_points, planner_data.ego_pose, stop_traj_points.at(wall_idx).pose,
tier4_planning_msgs::msg::PlanningFactor::NONE,
tier4_planning_msgs::msg::SafetyFactorArray{});
velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray(
planner_data.current_time, PlanningBehavior::ADAPTIVE_CRUISE,
stop_traj_points.at(wall_idx).pose));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -338,6 +338,10 @@ std::vector<TrajectoryPoint> PlannerInterface::generateStopTrajectory(
const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose;
velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray(
planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, stop_pose));
planning_factor_interface_->add(
output_traj_points, planner_data.ego_pose, stop_pose,
tier4_planning_msgs::msg::PlanningFactor::STOP,
tier4_planning_msgs::msg::SafetyFactorArray{});
// Store stop reason debug data
debug_data_ptr_->stop_metrics =
makeMetrics("PlannerInterface", "stop", planner_data, stop_pose, *determined_stop_obstacle);
Expand Down Expand Up @@ -594,6 +598,13 @@ std::vector<TrajectoryPoint> PlannerInterface::generateSlowDownTrajectory(
planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE,
slow_down_traj_points.at(slow_down_wall_idx).pose));
autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker);
planning_factor_interface_->add(
slow_down_traj_points, planner_data.ego_pose,
slow_down_traj_points.at(*slow_down_start_idx).pose,
slow_down_traj_points.at(*slow_down_end_idx).pose,
tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
tier4_planning_msgs::msg::SafetyFactorArray{}, planner_data.is_driving_forward,
stable_slow_down_vel);
}

// add debug virtual wall
Expand Down
Loading