@@ -1554,27 +1554,9 @@ bool GoalPlannerModule::checkObjectsCollision(
1554
1554
}
1555
1555
1556
1556
/* Expand ego collision check polygon
1557
- * - `collision_check_margin` in all directions
1558
- * - `extra_stopping_margin` in the moving direction
1559
- * - `extra_lateral_margin` in external direction of path curve
1560
- *
1561
- *
1562
- * ^ moving direction
1563
- * x
1564
- * x
1565
- * x
1566
- * +----------------------+------x--+
1567
- * | | x |
1568
- * | +---------------+ | xx |
1569
- * | | | | xx |
1570
- * | | ego footprint |xxxxx |
1571
- * | | | | |
1572
- * | +---------------+ | extra_stopping_margin
1573
- * | margin | |
1574
- * +----------------------+ |
1575
- * | extra_lateral_margin |
1576
- * +--------------------------------+
1577
- *
1557
+ * - `collision_check_margin` is added in all directions.
1558
+ * - `extra_stopping_margin` adds stopping margin under deceleration constraints forward.
1559
+ * - `extra_lateral_margin` adds the latearl margin on curves.
1578
1560
*/
1579
1561
std::vector<Polygon2d> ego_polygons_expanded{};
1580
1562
const auto curvatures = motion_utils::calcCurvature (path.points );
@@ -1585,19 +1567,19 @@ bool GoalPlannerModule::checkObjectsCollision(
1585
1567
std::pow (p.point .longitudinal_velocity_mps , 2 ) * 0.5 / parameters_->maximum_deceleration ,
1586
1568
parameters_->object_recognition_collision_check_max_extra_stopping_margin );
1587
1569
1588
- double extra_lateral_margin = (-1 ) * curvatures.at (i) * p.point .longitudinal_velocity_mps *
1589
- std::abs (p.point .longitudinal_velocity_mps );
1590
- extra_lateral_margin =
1591
- std::clamp (extra_lateral_margin, -extra_stopping_margin, extra_stopping_margin);
1570
+ // The square is meant to imply centrifugal force, but it is not a very well-founded formula.
1571
+ // TODO(kosuke55): It is needed to consider better way because there is an inherently different
1572
+ // conception of the inside and outside margins.
1573
+ const double extra_lateral_margin = std::min (
1574
+ extra_stopping_margin,
1575
+ std::abs (curvatures.at (i) * std::pow (p.point .longitudinal_velocity_mps , 2 )));
1592
1576
1593
- const auto lateral_offset_pose =
1594
- tier4_autoware_utils::calcOffsetPose (p.point .pose , 0.0 , extra_lateral_margin / 2.0 , 0.0 );
1595
1577
const auto ego_polygon = tier4_autoware_utils::toFootprint (
1596
- lateral_offset_pose ,
1578
+ p. point . pose ,
1597
1579
planner_data_->parameters .base_link2front + collision_check_margin + extra_stopping_margin,
1598
1580
planner_data_->parameters .base_link2rear + collision_check_margin,
1599
1581
planner_data_->parameters .vehicle_width + collision_check_margin * 2.0 +
1600
- std::abs ( extra_lateral_margin) );
1582
+ extra_lateral_margin * 2.0 );
1601
1583
ego_polygons_expanded.push_back (ego_polygon);
1602
1584
}
1603
1585
0 commit comments