@@ -1565,27 +1565,9 @@ bool GoalPlannerModule::checkObjectsCollision(
1565
1565
}
1566
1566
1567
1567
/* 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.
1589
1571
*/
1590
1572
std::vector<Polygon2d> ego_polygons_expanded{};
1591
1573
const auto curvatures = motion_utils::calcCurvature (path.points );
@@ -1596,19 +1578,19 @@ bool GoalPlannerModule::checkObjectsCollision(
1596
1578
std::pow (p.point .longitudinal_velocity_mps , 2 ) * 0.5 / parameters_->maximum_deceleration ,
1597
1579
parameters_->object_recognition_collision_check_max_extra_stopping_margin );
1598
1580
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 )));
1603
1587
1604
- const auto lateral_offset_pose =
1605
- tier4_autoware_utils::calcOffsetPose (p.point .pose , 0.0 , extra_lateral_margin / 2.0 , 0.0 );
1606
1588
const auto ego_polygon = tier4_autoware_utils::toFootprint (
1607
- lateral_offset_pose ,
1589
+ p. point . pose ,
1608
1590
planner_data_->parameters .base_link2front + collision_check_margin + extra_stopping_margin,
1609
1591
planner_data_->parameters .base_link2rear + collision_check_margin,
1610
1592
planner_data_->parameters .vehicle_width + collision_check_margin * 2.0 +
1611
- std::abs ( extra_lateral_margin) );
1593
+ extra_lateral_margin * 2.0 );
1612
1594
ego_polygons_expanded.push_back (ego_polygon);
1613
1595
}
1614
1596
0 commit comments