Skip to content

Commit 5d5c1d9

Browse files
committed
feat(goal_planner): add extra_lateral_margin to both side (autowarefoundation#6222)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 7c09742 commit 5d5c1d9

File tree

1 file changed

+11
-29
lines changed

1 file changed

+11
-29
lines changed

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+11-29
Original file line numberDiff line numberDiff line change
@@ -1565,27 +1565,9 @@ bool GoalPlannerModule::checkObjectsCollision(
15651565
}
15661566

15671567
/* Expand ego collision check polygon
1568-
* - `collision_check_margin` in all directions
1569-
* - `extra_stopping_margin` in the moving direction
1570-
* - `extra_lateral_margin` in external direction of path curve
1571-
*
1572-
*
1573-
* ^ moving direction
1574-
* x
1575-
* x
1576-
* x
1577-
* +----------------------+------x--+
1578-
* | | x |
1579-
* | +---------------+ | xx |
1580-
* | | | | xx |
1581-
* | | ego footprint |xxxxx |
1582-
* | | | | |
1583-
* | +---------------+ | extra_stopping_margin
1584-
* | margin | |
1585-
* +----------------------+ |
1586-
* | extra_lateral_margin |
1587-
* +--------------------------------+
1588-
*
1568+
* - `collision_check_margin` is added in all directions.
1569+
* - `extra_stopping_margin` adds stopping margin under deceleration constraints forward.
1570+
* - `extra_lateral_margin` adds the lateral margin on curves.
15891571
*/
15901572
std::vector<Polygon2d> ego_polygons_expanded{};
15911573
const auto curvatures = motion_utils::calcCurvature(path.points);
@@ -1596,19 +1578,19 @@ bool GoalPlannerModule::checkObjectsCollision(
15961578
std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration,
15971579
parameters_->object_recognition_collision_check_max_extra_stopping_margin);
15981580

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

1604-
const auto lateral_offset_pose =
1605-
tier4_autoware_utils::calcOffsetPose(p.point.pose, 0.0, extra_lateral_margin / 2.0, 0.0);
16061588
const auto ego_polygon = tier4_autoware_utils::toFootprint(
1607-
lateral_offset_pose,
1589+
p.point.pose,
16081590
planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin,
16091591
planner_data_->parameters.base_link2rear + collision_check_margin,
16101592
planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 +
1611-
std::abs(extra_lateral_margin));
1593+
extra_lateral_margin * 2.0);
16121594
ego_polygons_expanded.push_back(ego_polygon);
16131595
}
16141596

0 commit comments

Comments
 (0)