Skip to content

Commit 5d520f9

Browse files
committed
feat(out_of_lane): use planning factor
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent c10a410 commit 5d520f9

File tree

2 files changed

+7
-0
lines changed

2 files changed

+7
-0
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,9 @@ void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name)
6060
init_parameters(node);
6161
velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE);
6262

63+
planning_factor_interface_ =
64+
std::make_unique<autoware::motion_utils::PlanningFactorInterface>(&node, "out_of_lane");
65+
6366
debug_publisher_ =
6467
node.create_publisher<visualization_msgs::msg::MarkerArray>("~/" + ns_ + "/debug_markers", 1);
6568
virtual_wall_publisher_ =
@@ -315,6 +318,9 @@ VelocityPlanningResult OutOfLaneModule::plan(
315318
planner_data->current_odometry.twist.twist.linear.x > 0.1;
316319
const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING
317320
: motion_utils::VelocityFactor::STOPPED;
321+
planning_factor_interface_->add(
322+
ego_trajectory_points, ego_data.pose, *slowdown_pose, PlanningFactor::SLOW_DOWN,
323+
SafetyFactorArray{});
318324
velocity_factor_interface_.set(
319325
ego_trajectory_points, ego_data.pose, *slowdown_pose, status, "out_of_lane");
320326
result.velocity_factor = velocity_factor_interface_.get();

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ class OutOfLaneModule : public PluginModuleInterface
4040
{
4141
public:
4242
void init(rclcpp::Node & node, const std::string & module_name) override;
43+
void publish_planning_factor() override { planning_factor_interface_->publish(); };
4344
void update_parameters(const std::vector<rclcpp::Parameter> & parameters) override;
4445
VelocityPlanningResult plan(
4546
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & ego_trajectory_points,

0 commit comments

Comments
 (0)