Skip to content

Commit 8549d9f

Browse files
maxime-clemkarishma1911
authored andcommitted
feat(out_of_lane): set velocity_factor to ROUTE_OBSTACLE (autowarefoundation#6668)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent e5fdea8 commit 8549d9f

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ OutOfLaneModule::OutOfLaneModule(
5252
const rclcpp::Clock::SharedPtr clock)
5353
: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param))
5454
{
55-
velocity_factor_.init(PlanningBehavior::UNKNOWN);
55+
velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE);
5656
}
5757

5858
bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
@@ -175,7 +175,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
175175
}
176176
velocity_factor_.set(
177177
path->points, planner_data_->current_odometry->pose, point_to_insert->point.point.pose,
178-
VelocityFactor::UNKNOWN);
178+
VelocityFactor::ROUTE_OBSTACLE);
179179
} else if (!decisions.empty()) {
180180
RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)");
181181
}

0 commit comments

Comments
 (0)