Skip to content

Commit bfce3dd

Browse files
rename function is_colliding
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent f5dd4e7 commit bfce3dd

File tree

2 files changed

+9
-9
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_lane_change_module

2 files changed

+9
-9
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ class NormalLaneChange : public LaneChangeBase
145145
const utils::path_safety_checker::RSSparams & rss_params,
146146
CollisionCheckDebugMap & debug_data) const;
147147

148-
bool is_collided(
148+
bool is_colliding(
149149
const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj,
150150
const std::vector<PoseWithVelocityStamped> & ego_predicted_path,
151151
const RSSparams & selected_rss_param, const bool check_prepare_phase,

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -1522,7 +1522,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
15221522
const auto selected_rss_param = (object.initial_twist.linear.x <= stopped_obj_vel_th)
15231523
? lane_change_parameters_->safety.rss_params_for_parked
15241524
: rss_params;
1525-
return is_collided(
1525+
return is_colliding(
15261526
lane_change_path, object, ego_predicted_path, selected_rss_param, is_check_prepare_phase,
15271527
debug_data);
15281528
};
@@ -1541,28 +1541,28 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
15411541
return {is_safe, !is_object_behind_ego};
15421542
}
15431543

1544-
bool NormalLaneChange::is_collided(
1544+
bool NormalLaneChange::is_colliding(
15451545
const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj,
15461546
const std::vector<PoseWithVelocityStamped> & ego_predicted_path,
15471547
const RSSparams & selected_rss_param, const bool check_prepare_phase,
15481548
CollisionCheckDebugMap & debug_data) const
15491549
{
1550-
constexpr auto is_collided{true};
1550+
constexpr auto is_colliding{true};
15511551

15521552
if (lane_change_path.path.points.empty()) {
1553-
return !is_collided;
1553+
return !is_colliding;
15541554
}
15551555

15561556
if (ego_predicted_path.empty()) {
1557-
return !is_collided;
1557+
return !is_colliding;
15581558
}
15591559

15601560
const auto & lanes_polygon_ptr = common_data_ptr_->lanes_polygon_ptr;
15611561
const auto & current_polygon = lanes_polygon_ptr->current;
15621562
const auto & expanded_target_polygon = lanes_polygon_ptr->target;
15631563

15641564
if (current_polygon.empty() || expanded_target_polygon.empty()) {
1565-
return !is_collided;
1565+
return !is_colliding;
15661566
}
15671567

15681568
constexpr auto is_safe{true};
@@ -1613,10 +1613,10 @@ bool NormalLaneChange::is_collided(
16131613

16141614
utils::path_safety_checker::updateCollisionCheckDebugMap(
16151615
debug_data, current_debug_data, !is_safe);
1616-
return is_collided;
1616+
return is_colliding;
16171617
}
16181618
utils::path_safety_checker::updateCollisionCheckDebugMap(debug_data, current_debug_data, is_safe);
1619-
return !is_collided;
1619+
return !is_colliding;
16201620
}
16211621

16221622
double NormalLaneChange::get_max_velocity_for_safety_check() const

0 commit comments

Comments
 (0)