@@ -97,7 +97,7 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
97
97
lane_change_parameters_->rss_params_for_stuck , is_stuck);
98
98
}
99
99
100
- debug_valid_path_ = valid_paths;
100
+ lane_change_debug_. valid_paths = valid_paths;
101
101
102
102
if (valid_paths.empty ()) {
103
103
safe_path.info .current_lanes = current_lanes;
@@ -421,13 +421,8 @@ void NormalLaneChange::resetParameters()
421
421
current_lane_change_state_ = LaneChangeStates::Normal;
422
422
abort_path_ = nullptr ;
423
423
status_ = {};
424
+ lane_change_debug_.reset ();
424
425
425
- object_debug_.clear ();
426
- object_debug_after_approval_.clear ();
427
- debug_filtered_objects_.current_lane .clear ();
428
- debug_filtered_objects_.target_lane .clear ();
429
- debug_filtered_objects_.other_lane .clear ();
430
- debug_valid_path_.clear ();
431
426
RCLCPP_DEBUG (logger_, " reset all flags and debug information." );
432
427
}
433
428
@@ -1112,7 +1107,7 @@ bool NormalLaneChange::getLaneChangePaths(
1112
1107
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
1113
1108
const bool check_safety) const
1114
1109
{
1115
- object_debug_ .clear ();
1110
+ lane_change_debug_. collision_check_objects .clear ();
1116
1111
if (current_lanes.empty () || target_lanes.empty ()) {
1117
1112
RCLCPP_WARN (logger_, " target_neighbor_preferred_lane_poly_2d is empty. Not expected." );
1118
1113
return false ;
@@ -1158,7 +1153,7 @@ bool NormalLaneChange::getLaneChangePaths(
1158
1153
}
1159
1154
1160
1155
const auto target_objects = getTargetObjects (current_lanes, target_lanes);
1161
- debug_filtered_objects_ = target_objects;
1156
+ lane_change_debug_. filtered_objects = target_objects;
1162
1157
1163
1158
const auto prepare_durations = calcPrepareDuration (current_lanes, target_lanes);
1164
1159
@@ -1385,9 +1380,10 @@ bool NormalLaneChange::getLaneChangePaths(
1385
1380
std::vector<ExtendedPredictedObject> filtered_objects =
1386
1381
filterObjectsInTargetLane (target_objects, target_lanes);
1387
1382
if (
1388
- !is_stuck && utils::lane_change::passParkedObject (
1389
- route_handler, *candidate_path, filtered_objects, lane_change_buffer,
1390
- is_goal_in_route, *lane_change_parameters_, object_debug_)) {
1383
+ !is_stuck &&
1384
+ utils::lane_change::passParkedObject (
1385
+ route_handler, *candidate_path, filtered_objects, lane_change_buffer, is_goal_in_route,
1386
+ *lane_change_parameters_, lane_change_debug_.collision_check_objects )) {
1391
1387
debug_print (
1392
1388
" Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip "
1393
1389
" lane change." );
@@ -1400,7 +1396,8 @@ bool NormalLaneChange::getLaneChangePaths(
1400
1396
}
1401
1397
1402
1398
const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe (
1403
- *candidate_path, target_objects, rss_params, is_stuck, object_debug_);
1399
+ *candidate_path, target_objects, rss_params, is_stuck,
1400
+ lane_change_debug_.collision_check_objects );
1404
1401
1405
1402
if (is_safe) {
1406
1403
debug_print (" ACCEPT!!!: it is valid and safe!" );
@@ -1423,24 +1420,25 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
1423
1420
const auto & target_lanes = status_.target_lanes ;
1424
1421
1425
1422
const auto target_objects = getTargetObjects (current_lanes, target_lanes);
1426
- debug_filtered_objects_ = target_objects;
1423
+ lane_change_debug_. filtered_objects = target_objects;
1427
1424
1428
1425
CollisionCheckDebugMap debug_data;
1429
1426
const bool is_stuck = isVehicleStuck (current_lanes);
1430
1427
const auto safety_status = isLaneChangePathSafe (
1431
1428
path, target_objects, lane_change_parameters_->rss_params_for_abort , is_stuck, debug_data);
1432
1429
{
1433
1430
// only for debug purpose
1434
- object_debug_.clear ();
1435
- object_debug_lifetime_ += (stop_watch_.toc (getModuleTypeStr ()) / 1000 );
1436
- if (object_debug_lifetime_ > 2.0 ) {
1431
+ lane_change_debug_.collision_check_objects .clear ();
1432
+ lane_change_debug_.collision_check_object_debug_lifetime +=
1433
+ (stop_watch_.toc (getModuleTypeStr ()) / 1000 );
1434
+ if (lane_change_debug_.collision_check_object_debug_lifetime > 2.0 ) {
1437
1435
stop_watch_.toc (getModuleTypeStr (), true );
1438
- object_debug_lifetime_ = 0.0 ;
1439
- object_debug_after_approval_ .clear ();
1436
+ lane_change_debug_. collision_check_object_debug_lifetime = 0.0 ;
1437
+ lane_change_debug_. collision_check_objects_after_approval .clear ();
1440
1438
}
1441
1439
1442
1440
if (!safety_status.is_safe ) {
1443
- object_debug_after_approval_ = debug_data;
1441
+ lane_change_debug_. collision_check_objects_after_approval = debug_data;
1444
1442
}
1445
1443
}
1446
1444
@@ -1802,7 +1800,7 @@ bool NormalLaneChange::isVehicleStuck(
1802
1800
using lanelet::utils::getArcCoordinates;
1803
1801
const auto base_distance = getArcCoordinates (current_lanes, getEgoPose ()).length ;
1804
1802
1805
- for (const auto & object : debug_filtered_objects_ .current_lane ) {
1803
+ for (const auto & object : lane_change_debug_. filtered_objects .current_lane ) {
1806
1804
const auto & p = object.initial_pose .pose ; // TODO(Horibe): consider footprint point
1807
1805
1808
1806
// Note: it needs chattering prevention.
0 commit comments