|
17 | 17 | #include "behavior_path_planner_common/utils/parking_departure/utils.hpp"
|
18 | 18 | #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
|
19 | 19 | #include "behavior_path_planner_common/utils/path_utils.hpp"
|
| 20 | +#include "behavior_path_start_planner_module/debug.hpp" |
20 | 21 | #include "behavior_path_start_planner_module/util.hpp"
|
21 | 22 | #include "motion_utils/trajectory/trajectory.hpp"
|
22 | 23 |
|
@@ -126,7 +127,7 @@ void StartPlannerModule::initVariables()
|
126 | 127 | resetPathReference();
|
127 | 128 | debug_marker_.markers.clear();
|
128 | 129 | initializeSafetyCheckParameters();
|
129 |
| - initializeCollisionCheckDebugMap(start_planner_data_.collision_check); |
| 130 | + initializeCollisionCheckDebugMap(debug_data_.collision_check); |
130 | 131 | }
|
131 | 132 |
|
132 | 133 | void StartPlannerModule::updateEgoPredictedPathParams(
|
@@ -589,8 +590,8 @@ void StartPlannerModule::planWithPriority(
|
589 | 590 | if (findPullOutPath(
|
590 | 591 | start_pose_candidates[index], planner, refined_start_pose, goal_pose,
|
591 | 592 | collision_check_margin)) {
|
592 |
| - start_planner_data_.selected_start_pose_candidate_index = index; |
593 |
| - start_planner_data_.margin_for_start_pose_candidate = collision_check_margin; |
| 593 | + debug_data_.selected_start_pose_candidate_index = index; |
| 594 | + debug_data_.margin_for_start_pose_candidate = collision_check_margin; |
594 | 595 | return;
|
595 | 596 | }
|
596 | 597 | }
|
@@ -848,8 +849,8 @@ void StartPlannerModule::updatePullOutStatus()
|
848 | 849 | start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority);
|
849 | 850 | }
|
850 | 851 |
|
851 |
| - start_planner_data_.refined_start_pose = *refined_start_pose; |
852 |
| - start_planner_data_.start_pose_candidates = start_pose_candidates; |
| 852 | + debug_data_.refined_start_pose = *refined_start_pose; |
| 853 | + debug_data_.start_pose_candidates = start_pose_candidates; |
853 | 854 | const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
|
854 | 855 | planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
|
855 | 856 |
|
@@ -1196,14 +1197,13 @@ bool StartPlannerModule::isSafePath() const
|
1196 | 1197 | const double hysteresis_factor =
|
1197 | 1198 | status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate;
|
1198 | 1199 |
|
1199 |
| - utils::parking_departure::updateSafetyCheckTargetObjectsData( |
1200 |
| - start_planner_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); |
| 1200 | + behavior_path_planner::updateSafetyCheckDebugData( |
| 1201 | + debug_data_, filtered_objects, target_objects_on_lane, ego_predicted_path); |
1201 | 1202 |
|
1202 | 1203 | return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
|
1203 | 1204 | pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane,
|
1204 |
| - start_planner_data_.collision_check, planner_data_->parameters, |
1205 |
| - safety_check_params_->rss_params, objects_filtering_params_->use_all_predicted_path, |
1206 |
| - hysteresis_factor); |
| 1205 | + debug_data_.collision_check, planner_data_->parameters, safety_check_params_->rss_params, |
| 1206 | + objects_filtering_params_->use_all_predicted_path, hysteresis_factor); |
1207 | 1207 | }
|
1208 | 1208 |
|
1209 | 1209 | bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const
|
@@ -1354,7 +1354,7 @@ void StartPlannerModule::setDebugData()
|
1354 | 1354 | add(createPoseMarkerArray(status_.pull_out_path.start_pose, "start_pose", 0, 0.3, 0.9, 0.3));
|
1355 | 1355 | add(createPoseMarkerArray(status_.pull_out_path.end_pose, "end_pose", 0, 0.9, 0.9, 0.3));
|
1356 | 1356 | add(createFootprintMarkerArray(
|
1357 |
| - start_planner_data_.refined_start_pose, vehicle_info_, "refined_start_pose", 0, 0.9, 0.9, 0.3)); |
| 1357 | + debug_data_.refined_start_pose, vehicle_info_, "refined_start_pose", 0, 0.9, 0.9, 0.3)); |
1358 | 1358 | add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9));
|
1359 | 1359 | add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0));
|
1360 | 1360 |
|
@@ -1399,14 +1399,13 @@ void StartPlannerModule::setDebugData()
|
1399 | 1399 | visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple);
|
1400 | 1400 | footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
|
1401 | 1401 | text_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
|
1402 |
| - for (size_t i = 0; i < start_planner_data_.start_pose_candidates.size(); ++i) { |
| 1402 | + for (size_t i = 0; i < debug_data_.start_pose_candidates.size(); ++i) { |
1403 | 1403 | footprint_marker.id = i;
|
1404 | 1404 | text_marker.id = i;
|
1405 | 1405 | footprint_marker.points.clear();
|
1406 | 1406 | text_marker.text = "idx[" + std::to_string(i) + "]";
|
1407 |
| - text_marker.pose = start_planner_data_.start_pose_candidates.at(i); |
1408 |
| - addFootprintMarker( |
1409 |
| - footprint_marker, start_planner_data_.start_pose_candidates.at(i), vehicle_info_); |
| 1407 | + text_marker.pose = debug_data_.start_pose_candidates.at(i); |
| 1408 | + addFootprintMarker(footprint_marker, debug_data_.start_pose_candidates.at(i), vehicle_info_); |
1410 | 1409 | start_pose_footprint_marker_array.markers.push_back(footprint_marker);
|
1411 | 1410 | start_pose_text_marker_array.markers.push_back(text_marker);
|
1412 | 1411 | }
|
@@ -1450,29 +1449,29 @@ void StartPlannerModule::setDebugData()
|
1450 | 1449 |
|
1451 | 1450 | // safety check
|
1452 | 1451 | if (parameters_->safety_check_params.enable_safety_check) {
|
1453 |
| - if (start_planner_data_.ego_predicted_path.size() > 0) { |
| 1452 | + if (debug_data_.ego_predicted_path.size() > 0) { |
1454 | 1453 | const auto & ego_predicted_path = utils::path_safety_checker::convertToPredictedPath(
|
1455 |
| - start_planner_data_.ego_predicted_path, ego_predicted_path_params_->time_resolution); |
| 1454 | + debug_data_.ego_predicted_path, ego_predicted_path_params_->time_resolution); |
1456 | 1455 | add(createPredictedPathMarkerArray(
|
1457 | 1456 | ego_predicted_path, vehicle_info_, "ego_predicted_path_start_planner", 0, 0.0, 0.5, 0.9));
|
1458 | 1457 | }
|
1459 | 1458 |
|
1460 |
| - if (start_planner_data_.filtered_objects.objects.size() > 0) { |
| 1459 | + if (debug_data_.filtered_objects.objects.size() > 0) { |
1461 | 1460 | add(createObjectsMarkerArray(
|
1462 |
| - start_planner_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); |
| 1461 | + debug_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); |
1463 | 1462 | }
|
1464 | 1463 |
|
1465 |
| - add(showSafetyCheckInfo(start_planner_data_.collision_check, "object_debug_info")); |
1466 |
| - add(showPredictedPath(start_planner_data_.collision_check, "ego_predicted_path")); |
1467 |
| - add(showPolygon(start_planner_data_.collision_check, "ego_and_target_polygon_relation")); |
| 1464 | + add(showSafetyCheckInfo(debug_data_.collision_check, "object_debug_info")); |
| 1465 | + add(showPredictedPath(debug_data_.collision_check, "ego_predicted_path")); |
| 1466 | + add(showPolygon(debug_data_.collision_check, "ego_and_target_polygon_relation")); |
1468 | 1467 |
|
1469 | 1468 | // set objects of interest
|
1470 |
| - for (const auto & [uuid, data] : start_planner_data_.collision_check) { |
| 1469 | + for (const auto & [uuid, data] : debug_data_.collision_check) { |
1471 | 1470 | const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED;
|
1472 | 1471 | setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color);
|
1473 | 1472 | }
|
1474 | 1473 |
|
1475 |
| - initializeCollisionCheckDebugMap(start_planner_data_.collision_check); |
| 1474 | + initializeCollisionCheckDebugMap(debug_data_.collision_check); |
1476 | 1475 | }
|
1477 | 1476 |
|
1478 | 1477 | // Visualize planner type text
|
|
0 commit comments