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

feat(lane_change): add param for a lateral distance margin where the abort can be performed #4083

Merged
merged 6 commits into from
Jun 27, 2023
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 @@ -57,6 +57,7 @@
delta_time: 1.0 # [s]
duration: 5.0 # [s]
max_lateral_jerk: 1000.0 # [m/s3]
overhang_tolerance: 0.0 # [m]

finish_judge_lateral_threshold: 0.2 # [m]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,13 +301,14 @@ The following parameters are configurable in `behavior_path_planner.param.yaml`.

The following parameters are configurable in `lane_change.param.yaml`.

| Name | Unit | Type | Description | Default value |
| :------------------------------------- | ------- | ------- | -------------------------------------------------------------- | ------------- |
| `cancel.enable_on_prepare_phase` | [-] | boolean | Enable cancel lane change | true |
| `cancel.enable_on_lane_changing_phase` | [-] | boolean | Enable abort lane change. | false |
| `cancel.delta_time` | [s] | double | The time taken to start steering to return to the center line. | 3.0 |
| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 |
| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 |
| Name | Unit | Type | Description | Default value |
| :------------------------------------- | ------- | ------- | ---------------------------------------------------------------------------------------------------------------- | ------------- |
| `cancel.enable_on_prepare_phase` | [-] | boolean | Enable cancel lane change | true |
| `cancel.enable_on_lane_changing_phase` | [-] | boolean | Enable abort lane change. | false |
| `cancel.delta_time` | [s] | double | The time taken to start steering to return to the center line. | 3.0 |
| `cancel.duration` | [s] | double | The time taken to complete returning to the center line. | 3.0 |
| `cancel.max_lateral_jerk` | [m/sss] | double | The maximum lateral jerk for abort path | 1000.0 |
| `cancel.overhang_tolerance` | [m] | double | Lane change cancel is prohibited if the vehicle head exceeds the lane boundary more than this tolerance distance | 0.0 |

### Debug

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ struct LaneChangeCancelParameters
double delta_time{1.0};
double duration{5.0};
double max_lateral_jerk{10.0};
double overhang_tolerance{0.0};
};
struct LaneChangeParameters
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,7 @@ bool isEgoOutOfRoute(

bool isEgoWithinOriginalLane(
const lanelet::ConstLanelets & current_lanes, const Pose & current_pose,
const BehaviorPathPlannerParameters & common_param);
const BehaviorPathPlannerParameters & common_param, const double outer_margin = 0.0);

// path management

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -833,6 +833,7 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam()
p.cancel.delta_time = declare_parameter<double>(parameter("cancel.delta_time"));
p.cancel.duration = declare_parameter<double>(parameter("cancel.duration"));
p.cancel.max_lateral_jerk = declare_parameter<double>(parameter("cancel.max_lateral_jerk"));
p.cancel.overhang_tolerance = declare_parameter<double>(parameter("cancel.overhang_tolerance"));

p.finish_judge_lateral_threshold =
declare_parameter<double>("lane_change.finish_judge_lateral_threshold");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -395,7 +395,8 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const
if (dist > estimated_travel_dist) {
const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose;
return utils::isEgoWithinOriginalLane(
status_.current_lanes, estimated_pose, planner_data_->parameters);
status_.current_lanes, estimated_pose, planner_data_->parameters,
lane_change_parameters_->cancel.overhang_tolerance);
}
}

Expand Down
16 changes: 12 additions & 4 deletions planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1114,7 +1114,7 @@ bool isEgoOutOfRoute(

bool isEgoWithinOriginalLane(
const lanelet::ConstLanelets & current_lanes, const Pose & current_pose,
const BehaviorPathPlannerParameters & common_param)
const BehaviorPathPlannerParameters & common_param, const double outer_margin)
{
const auto lane_length = lanelet::utils::getLaneletLength2d(current_lanes);
const auto lane_poly = lanelet::utils::getPolygonFromArcLength(current_lanes, 0, lane_length);
Expand All @@ -1124,9 +1124,17 @@ bool isEgoWithinOriginalLane(
const auto vehicle_poly =
tier4_autoware_utils::toFootprint(current_pose, base_link2front, base_link2rear, vehicle_width);

// Check if the ego vehicle is entirely within the lane by checking if the vehicle's polygon
// is within the lane's polygon
return boost::geometry::within(vehicle_poly, lanelet::utils::to2D(lane_poly).basicPolygon());
// Check if the ego vehicle is entirely within the lane with a given outer margin.
for (const auto & p : vehicle_poly.outer()) {
// When the point is in the polygon, the distance is 0. When it is out of the polygon, return a
// positive value.
const auto dist = boost::geometry::distance(p, lanelet::utils::to2D(lane_poly).basicPolygon());
if (dist > std::max(outer_margin, 0.0)) {
return false; // out of polygon
}
}

return true; // inside polygon
}

lanelet::ConstLanelets transformToLanelets(const DrivableLanes & drivable_lanes)
Expand Down