Skip to content

Commit

Permalink
feat(goal_planner): add extra_lateral_margin to both side
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Jan 30, 2024
1 parent ba21eec commit 662779b
Showing 1 changed file with 11 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1554,27 +1554,9 @@ bool GoalPlannerModule::checkObjectsCollision(
}

/* Expand ego collision check polygon
* - `collision_check_margin` in all directions
* - `extra_stopping_margin` in the moving direction
* - `extra_lateral_margin` in external direction of path curve
*
*
* ^ moving direction
* x
* x
* x
* +----------------------+------x--+
* | | x |
* | +---------------+ | xx |
* | | | | xx |
* | | ego footprint |xxxxx |
* | | | | |
* | +---------------+ | extra_stopping_margin
* | margin | |
* +----------------------+ |
* | extra_lateral_margin |
* +--------------------------------+
*
* - `collision_check_margin` is added in all directions.
* - `extra_stopping_margin` adds stopping margin under deceleration constraints forward.
* - `extra_lateral_margin` adds the latearl margin on curves.

Check warning on line 1559 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (latearl)

Check warning on line 1559 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (latearl)
*/
std::vector<Polygon2d> ego_polygons_expanded{};
const auto curvatures = motion_utils::calcCurvature(path.points);
Expand All @@ -1585,19 +1567,19 @@ bool GoalPlannerModule::checkObjectsCollision(
std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration,
parameters_->object_recognition_collision_check_max_extra_stopping_margin);

double extra_lateral_margin = (-1) * curvatures.at(i) * p.point.longitudinal_velocity_mps *
std::abs(p.point.longitudinal_velocity_mps);
extra_lateral_margin =
std::clamp(extra_lateral_margin, -extra_stopping_margin, extra_stopping_margin);
// The square is meant to imply centrifugal force, but it is not a very well-founded formula.
// TODO(kosuke55): It is needed to consider better way because there is an inherently different
// conception of the inside and outside margins.
const double extra_lateral_margin = std::min(
extra_stopping_margin,
std::abs(curvatures.at(i) * std::pow(p.point.longitudinal_velocity_mps, 2)));

Check warning on line 1575 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1575

Added line #L1575 was not covered by tests

const auto lateral_offset_pose =
tier4_autoware_utils::calcOffsetPose(p.point.pose, 0.0, extra_lateral_margin / 2.0, 0.0);
const auto ego_polygon = tier4_autoware_utils::toFootprint(
lateral_offset_pose,
p.point.pose,
planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin,
planner_data_->parameters.base_link2rear + collision_check_margin,
planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 +
std::abs(extra_lateral_margin));
extra_lateral_margin * 2.0);

Check warning on line 1582 in planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1582

Added line #L1582 was not covered by tests
ego_polygons_expanded.push_back(ego_polygon);
}

Expand Down

0 comments on commit 662779b

Please sign in to comment.