Skip to content

Commit d4a78a5

Browse files
committed
feat(out_of_lane): also apply lat buffer between the lane and stop pose (autowarefoundation#7918)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 73ed8b8 commit d4a78a5

File tree

5 files changed

+14
-7
lines changed

5 files changed

+14
-7
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,8 @@
2727
action: # action to insert in the trajectory if an object causes a conflict at an overlap
2828
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
2929
precision: 0.1 # [m] precision when inserting a stop pose in the trajectory
30-
distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane
30+
longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle
31+
lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle
3132
min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled
3233
slowdown:
3334
distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -70,9 +70,11 @@ std::optional<TrajectoryPoint> calculate_last_in_lane_pose(
7070

7171
std::optional<SlowdownToInsert> calculate_slowdown_point(
7272
const EgoData & ego_data, const std::vector<Slowdown> & decisions,
73-
const std::optional<SlowdownToInsert> prev_slowdown_point, PlannerParam params)
73+
const std::optional<SlowdownToInsert> & prev_slowdown_point, PlannerParam params)
7474
{
75-
params.extra_front_offset += params.dist_buffer;
75+
params.extra_front_offset += params.lon_dist_buffer;
76+
params.extra_right_offset += params.lat_dist_buffer;
77+
params.extra_left_offset += params.lat_dist_buffer;
7678
const auto base_footprint = make_base_footprint(params);
7779

7880
// search for the first slowdown decision for which a stop point can be inserted

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,6 @@ std::optional<TrajectoryPoint> calculate_last_in_lane_pose(
5353
/// @return optional slowdown point to insert in the trajectory
5454
std::optional<SlowdownToInsert> calculate_slowdown_point(
5555
const EgoData & ego_data, const std::vector<Slowdown> & decisions,
56-
const std::optional<SlowdownToInsert> prev_slowdown_point, PlannerParam params);
56+
const std::optional<SlowdownToInsert> & prev_slowdown_point, PlannerParam params);
5757
} // namespace autoware::motion_velocity_planner::out_of_lane
5858
#endif // CALCULATE_SLOWDOWN_POINTS_HPP_

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,9 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node)
9393
getOrDeclareParameter<bool>(node, ns_ + ".action.skip_if_over_max_decel");
9494
pp.precision = getOrDeclareParameter<double>(node, ns_ + ".action.precision");
9595
pp.min_decision_duration = getOrDeclareParameter<double>(node, ns_ + ".action.min_duration");
96-
pp.dist_buffer = getOrDeclareParameter<double>(node, ns_ + ".action.distance_buffer");
96+
pp.lon_dist_buffer =
97+
getOrDeclareParameter<double>(node, ns_ + ".action.longitudinal_distance_buffer");
98+
pp.lat_dist_buffer = getOrDeclareParameter<double>(node, ns_ + ".action.lateral_distance_buffer");
9799
pp.slow_velocity = getOrDeclareParameter<double>(node, ns_ + ".action.slowdown.velocity");
98100
pp.slow_dist_threshold =
99101
getOrDeclareParameter<double>(node, ns_ + ".action.slowdown.distance_threshold");
@@ -139,7 +141,8 @@ void OutOfLaneModule::update_parameters(const std::vector<rclcpp::Parameter> & p
139141
updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel);
140142
updateParam(parameters, ns_ + ".action.precision", pp.precision);
141143
updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration);
142-
updateParam(parameters, ns_ + ".action.distance_buffer", pp.dist_buffer);
144+
updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer);
145+
updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer);
143146
updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity);
144147
updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold);
145148
updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold);

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,8 @@ struct PlannerParam
6161
double overlap_min_dist; // [m] min distance inside another lane to consider an overlap
6262
// action to insert in the trajectory if an object causes a conflict at an overlap
6363
bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel
64-
double dist_buffer;
64+
double lon_dist_buffer; // [m] safety distance buffer to keep in front of the ego vehicle
65+
double lat_dist_buffer; // [m] safety distance buffer to keep on the side of the ego vehicle
6566
double slow_velocity;
6667
double slow_dist_threshold;
6768
double stop_dist_threshold;

0 commit comments

Comments
 (0)