@@ -1522,7 +1522,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
1522
1522
const auto selected_rss_param = (object.initial_twist .linear .x <= stopped_obj_vel_th)
1523
1523
? lane_change_parameters_->safety .rss_params_for_parked
1524
1524
: rss_params;
1525
- return is_collided (
1525
+ return is_colliding (
1526
1526
lane_change_path, object, ego_predicted_path, selected_rss_param, is_check_prepare_phase,
1527
1527
debug_data);
1528
1528
};
@@ -1541,28 +1541,28 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
1541
1541
return {is_safe, !is_object_behind_ego};
1542
1542
}
1543
1543
1544
- bool NormalLaneChange::is_collided (
1544
+ bool NormalLaneChange::is_colliding (
1545
1545
const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj,
1546
1546
const std::vector<PoseWithVelocityStamped> & ego_predicted_path,
1547
1547
const RSSparams & selected_rss_param, const bool check_prepare_phase,
1548
1548
CollisionCheckDebugMap & debug_data) const
1549
1549
{
1550
- constexpr auto is_collided {true };
1550
+ constexpr auto is_colliding {true };
1551
1551
1552
1552
if (lane_change_path.path .points .empty ()) {
1553
- return !is_collided ;
1553
+ return !is_colliding ;
1554
1554
}
1555
1555
1556
1556
if (ego_predicted_path.empty ()) {
1557
- return !is_collided ;
1557
+ return !is_colliding ;
1558
1558
}
1559
1559
1560
1560
const auto & lanes_polygon_ptr = common_data_ptr_->lanes_polygon_ptr ;
1561
1561
const auto & current_polygon = lanes_polygon_ptr->current ;
1562
1562
const auto & expanded_target_polygon = lanes_polygon_ptr->target ;
1563
1563
1564
1564
if (current_polygon.empty () || expanded_target_polygon.empty ()) {
1565
- return !is_collided ;
1565
+ return !is_colliding ;
1566
1566
}
1567
1567
1568
1568
constexpr auto is_safe{true };
@@ -1613,10 +1613,10 @@ bool NormalLaneChange::is_collided(
1613
1613
1614
1614
utils::path_safety_checker::updateCollisionCheckDebugMap (
1615
1615
debug_data, current_debug_data, !is_safe);
1616
- return is_collided ;
1616
+ return is_colliding ;
1617
1617
}
1618
1618
utils::path_safety_checker::updateCollisionCheckDebugMap (debug_data, current_debug_data, is_safe);
1619
- return !is_collided ;
1619
+ return !is_colliding ;
1620
1620
}
1621
1621
1622
1622
double NormalLaneChange::get_max_velocity_for_safety_check () const
0 commit comments