Skip to content

Commit f0deba8

Browse files
kyoichi-sugaharapre-commit-ci[bot]
authored andcommittedMay 28, 2024
refactor(start_planner): separate start planner parameters and debug data structure (#6101)
* Add data_structs.hpp and update include paths * Refactor start planner debug data structure * Update debug_data variable name in StartPlannerModule Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 2877cbf commit f0deba8

File tree

7 files changed

+118
-35
lines changed

7 files changed

+118
-35
lines changed
 

‎planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp

-5
Original file line numberDiff line numberDiff line change
@@ -38,11 +38,6 @@ struct StartGoalPlannerData
3838
std::vector<PoseWithVelocityStamped> ego_predicted_path;
3939
// collision check debug map
4040
CollisionCheckDebugMap collision_check;
41-
42-
Pose refined_start_pose;
43-
std::vector<Pose> start_pose_candidates;
44-
size_t selected_start_pose_candidate_index;
45-
double margin_for_start_pose_candidate;
4641
};
4742

4843
} // namespace behavior_path_planner
+23-3
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// See the License for the specific language governing permissions and
1414
// limitations under the License.
1515

16-
#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_
17-
#define BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_
16+
#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_
17+
#define BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_
1818

1919
#include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp"
2020
#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
@@ -29,10 +29,30 @@
2929
namespace behavior_path_planner
3030
{
3131

32+
using autoware_auto_perception_msgs::msg::PredictedObjects;
33+
using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap;
34+
using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
35+
using behavior_path_planner::utils::path_safety_checker::TargetObjectsOnLane;
36+
3237
using freespace_planning_algorithms::AstarParam;
3338
using freespace_planning_algorithms::PlannerCommonParam;
3439
using freespace_planning_algorithms::RRTStarParam;
3540

41+
struct StartPlannerDebugData
42+
{
43+
// filtered objects
44+
PredictedObjects filtered_objects;
45+
TargetObjectsOnLane target_objects_on_lane;
46+
std::vector<PoseWithVelocityStamped> ego_predicted_path;
47+
// collision check debug map
48+
CollisionCheckDebugMap collision_check;
49+
50+
Pose refined_start_pose;
51+
std::vector<Pose> start_pose_candidates;
52+
size_t selected_start_pose_candidate_index;
53+
double margin_for_start_pose_candidate;
54+
};
55+
3656
struct StartPlannerParameters
3757
{
3858
double th_arrived_distance{0.0};
@@ -105,4 +125,4 @@ struct StartPlannerParameters
105125

106126
} // namespace behavior_path_planner
107127

108-
#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__START_PLANNER_PARAMETERS_HPP_
128+
#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DATA_STRUCTS_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
// Copyright 2023 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_
16+
#define BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_
17+
18+
#include "behavior_path_start_planner_module/data_structs.hpp"
19+
20+
#include <string>
21+
#include <vector>
22+
23+
namespace behavior_path_planner
24+
{
25+
using behavior_path_planner::StartPlannerDebugData;
26+
27+
void updateSafetyCheckDebugData(
28+
StartPlannerDebugData & data, const PredictedObjects & filtered_objects,
29+
const TargetObjectsOnLane & target_objects_on_lane,
30+
const std::vector<PoseWithVelocityStamped> & ego_predicted_path)
31+
{
32+
data.filtered_objects = filtered_objects;
33+
data.target_objects_on_lane = target_objects_on_lane;
34+
data.ego_predicted_path = ego_predicted_path;
35+
}
36+
37+
} // namespace behavior_path_planner
38+
39+
#endif // BEHAVIOR_PATH_START_PLANNER_MODULE__DEBUG_HPP_

‎planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_
1717

1818
#include "behavior_path_planner_common/data_manager.hpp"
19+
#include "behavior_path_start_planner_module/data_structs.hpp"
1920
#include "behavior_path_start_planner_module/pull_out_path.hpp"
20-
#include "behavior_path_start_planner_module/start_planner_parameters.hpp"
2121

2222
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
2323
#include <geometry_msgs/msg/pose_stamped.hpp>

‎planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,11 @@
2121
#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
2222
#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"
2323
#include "behavior_path_planner_common/utils/utils.hpp"
24+
#include "behavior_path_start_planner_module/data_structs.hpp"
2425
#include "behavior_path_start_planner_module/freespace_pull_out.hpp"
2526
#include "behavior_path_start_planner_module/geometric_pull_out.hpp"
2627
#include "behavior_path_start_planner_module/pull_out_path.hpp"
2728
#include "behavior_path_start_planner_module/shift_pull_out.hpp"
28-
#include "behavior_path_start_planner_module/start_planner_parameters.hpp"
2929

3030
#include <lane_departure_checker/lane_departure_checker.hpp>
3131
#include <vehicle_info_util/vehicle_info.hpp>
@@ -191,7 +191,7 @@ class StartPlannerModule : public SceneModuleInterface
191191

192192
std::vector<std::shared_ptr<PullOutPlannerBase>> start_planners_;
193193
PullOutStatus status_;
194-
mutable StartGoalPlannerData start_planner_data_;
194+
mutable StartPlannerDebugData debug_data_;
195195

196196
std::deque<nav_msgs::msg::Odometry::ConstSharedPtr> odometry_buffer_;
197197

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
// Copyright 2023 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "behavior_path_start_planner_module/debug.hpp"
16+
17+
namespace behavior_path_planner
18+
{
19+
20+
void updateSafetyCheckDebugData(
21+
StartPlannerDebugData & data, const PredictedObjects & filtered_objects,
22+
const TargetObjectsOnLane & target_objects_on_lane,
23+
const std::vector<PoseWithVelocityStamped> & ego_predicted_path)
24+
{
25+
data.filtered_objects = filtered_objects;
26+
data.target_objects_on_lane = target_objects_on_lane;
27+
data.ego_predicted_path = ego_predicted_path;
28+
}
29+
30+
} // namespace behavior_path_planner

‎planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+23-24
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include "behavior_path_planner_common/utils/parking_departure/utils.hpp"
1818
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
1919
#include "behavior_path_planner_common/utils/path_utils.hpp"
20+
#include "behavior_path_start_planner_module/debug.hpp"
2021
#include "behavior_path_start_planner_module/util.hpp"
2122
#include "motion_utils/trajectory/trajectory.hpp"
2223

@@ -126,7 +127,7 @@ void StartPlannerModule::initVariables()
126127
resetPathReference();
127128
debug_marker_.markers.clear();
128129
initializeSafetyCheckParameters();
129-
initializeCollisionCheckDebugMap(start_planner_data_.collision_check);
130+
initializeCollisionCheckDebugMap(debug_data_.collision_check);
130131
}
131132

132133
void StartPlannerModule::updateEgoPredictedPathParams(
@@ -589,8 +590,8 @@ void StartPlannerModule::planWithPriority(
589590
if (findPullOutPath(
590591
start_pose_candidates[index], planner, refined_start_pose, goal_pose,
591592
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;
594595
return;
595596
}
596597
}
@@ -848,8 +849,8 @@ void StartPlannerModule::updatePullOutStatus()
848849
start_pose_candidates, *refined_start_pose, goal_pose, parameters_->search_priority);
849850
}
850851

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;
853854
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
854855
planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
855856

@@ -1196,14 +1197,13 @@ bool StartPlannerModule::isSafePath() const
11961197
const double hysteresis_factor =
11971198
status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate;
11981199

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);
12011202

12021203
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
12031204
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);
12071207
}
12081208

12091209
bool StartPlannerModule::isGoalBehindOfEgoInSameRouteSegment() const
@@ -1354,7 +1354,7 @@ void StartPlannerModule::setDebugData()
13541354
add(createPoseMarkerArray(status_.pull_out_path.start_pose, "start_pose", 0, 0.3, 0.9, 0.3));
13551355
add(createPoseMarkerArray(status_.pull_out_path.end_pose, "end_pose", 0, 0.9, 0.9, 0.3));
13561356
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));
13581358
add(createPathMarkerArray(getFullPath(), "full_path", 0, 0.0, 0.5, 0.9));
13591359
add(createPathMarkerArray(status_.backward_path, "backward_driving_path", 0, 0.0, 0.9, 0.0));
13601360

@@ -1399,14 +1399,13 @@ void StartPlannerModule::setDebugData()
13991399
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple);
14001400
footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14011401
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) {
14031403
footprint_marker.id = i;
14041404
text_marker.id = i;
14051405
footprint_marker.points.clear();
14061406
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_);
14101409
start_pose_footprint_marker_array.markers.push_back(footprint_marker);
14111410
start_pose_text_marker_array.markers.push_back(text_marker);
14121411
}
@@ -1450,29 +1449,29 @@ void StartPlannerModule::setDebugData()
14501449

14511450
// safety check
14521451
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) {
14541453
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);
14561455
add(createPredictedPathMarkerArray(
14571456
ego_predicted_path, vehicle_info_, "ego_predicted_path_start_planner", 0, 0.0, 0.5, 0.9));
14581457
}
14591458

1460-
if (start_planner_data_.filtered_objects.objects.size() > 0) {
1459+
if (debug_data_.filtered_objects.objects.size() > 0) {
14611460
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));
14631462
}
14641463

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"));
14681467

14691468
// 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) {
14711470
const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED;
14721471
setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color);
14731472
}
14741473

1475-
initializeCollisionCheckDebugMap(start_planner_data_.collision_check);
1474+
initializeCollisionCheckDebugMap(debug_data_.collision_check);
14761475
}
14771476

14781477
// Visualize planner type text

0 commit comments

Comments
 (0)