Skip to content

Commit cc266ea

Browse files
refactor(start_planner): visualize drivable lanes for shift path and pull_out_lanes for collision detection (#6110)
visualize drivable lanes for shift path and pull_out_lanes for collision detection Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent a1d4df1 commit cc266ea

File tree

6 files changed

+58
-27
lines changed

6 files changed

+58
-27
lines changed

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
center_line_path_interval: 1.0
1313
# shift pull out
1414
enable_shift_pull_out: true
15+
check_shift_path_lane_departure: true
1516
shift_collision_check_distance_from_end: -10.0
1617
minimum_shift_pull_out_distance: 0.0
1718
deceleration_interval: 15.0

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ struct StartPlannerDebugData
4646
std::vector<PoseWithVelocityStamped> ego_predicted_path;
4747
// collision check debug map
4848
CollisionCheckDebugMap collision_check;
49+
lanelet::ConstLanelets departure_check_lanes;
4950

5051
Pose refined_start_pose;
5152
std::vector<Pose> start_pose_candidates;

planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/shift_pull_out.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -50,9 +50,9 @@ class ShiftPullOut : public PullOutPlannerBase
5050
ShiftedPath & shifted_path, const Pose & start_pose, const Pose & end_pose,
5151
const double longitudinal_acc, const double lateral_acc);
5252

53-
void setDrivableLanes(const lanelet::ConstLanelets & drivable_lanes)
53+
void setDepartureCheckLanes(const lanelet::ConstLanelets & departure_check_lanes)
5454
{
55-
drivable_lanes_ = drivable_lanes;
55+
departure_check_lanes_ = departure_check_lanes;
5656
}
5757

5858
std::shared_ptr<LaneDepartureChecker> lane_departure_checker_;
@@ -64,7 +64,7 @@ class ShiftPullOut : public PullOutPlannerBase
6464
const double lon_acc, const double shift_time, const double shift_length,
6565
const double max_curvature, const double min_distance) const;
6666

67-
lanelet::ConstLanelets drivable_lanes_;
67+
lanelet::ConstLanelets departure_check_lanes_;
6868
};
6969
} // namespace behavior_path_planner
7070

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
@@ -244,8 +244,8 @@ class StartPlannerModule : public SceneModuleInterface
244244
const std::vector<PoseWithVelocityStamped> & ego_predicted_path) const;
245245
bool isSafePath() const;
246246
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;
247-
void updateDrivableLanes();
248-
lanelet::ConstLanelets createDrivableLanes() const;
247+
void updateDepartureCheckLanes();
248+
lanelet::ConstLanelets createDepartureCheckLanes() const;
249249

250250
// check if the goal is located behind the ego in the same route segment.
251251
bool isGoalBehindOfEgoInSameRouteSegment() const;

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

+9-2
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
8888
const auto transformed_vehicle_footprint =
8989
transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(pose));
9090
const bool is_out_of_lane =
91-
LaneDepartureChecker::isOutOfLane(drivable_lanes_, transformed_vehicle_footprint);
91+
LaneDepartureChecker::isOutOfLane(departure_check_lanes_, transformed_vehicle_footprint);
9292
if (i <= start_segment_idx) {
9393
if (!is_out_of_lane) {
9494
cropped_path.points.push_back(shift_path.points.at(i));
@@ -100,9 +100,16 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
100100
shift_path.points = cropped_path.points;
101101

102102
// check lane departure
103+
// The method for lane departure checking verifies if the footprint of each point on the path is
104+
// contained within a lanelet using `boost::geometry::within`, which incurs a high computational
105+
// cost.
106+
// TODO(someone): improve the method for detecting lane departures without using
107+
// lanelet::ConstLanelets, making it unnecessary to retain departure_check_lanes_ as a member
108+
// variable.
103109
if (
104110
parameters_.check_shift_path_lane_departure &&
105-
lane_departure_checker_->checkPathWillLeaveLane(drivable_lanes_, path_shift_start_to_end)) {
111+
lane_departure_checker_->checkPathWillLeaveLane(
112+
departure_check_lanes_, path_shift_start_to_end)) {
106113
continue;
107114
}
108115

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+42-20
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
#include <lanelet2_extension/utility/message_conversion.hpp>
2525
#include <lanelet2_extension/utility/query.hpp>
2626
#include <lanelet2_extension/utility/utilities.hpp>
27+
#include <lanelet2_extension/visualization/visualization.hpp>
2728
#include <magic_enum.hpp>
2829
#include <rclcpp/rclcpp.hpp>
2930

@@ -137,7 +138,7 @@ void StartPlannerModule::initVariables()
137138
debug_marker_.markers.clear();
138139
initializeSafetyCheckParameters();
139140
initializeCollisionCheckDebugMap(debug_data_.collision_check);
140-
updateDrivableLanes();
141+
updateDepartureCheckLanes();
141142
}
142143

143144
void StartPlannerModule::updateEgoPredictedPathParams(
@@ -597,7 +598,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
597598
void StartPlannerModule::resetStatus()
598599
{
599600
status_ = PullOutStatus{};
600-
updateDrivableLanes();
601+
updateDepartureCheckLanes();
601602
}
602603

603604
void StartPlannerModule::incrementPathIndex()
@@ -1244,8 +1245,12 @@ bool StartPlannerModule::isSafePath() const
12441245
const double hysteresis_factor =
12451246
status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate;
12461247

1247-
behavior_path_planner::updateSafetyCheckDebugData(
1248-
debug_data_, filtered_objects, target_objects_on_lane, ego_predicted_path);
1248+
// debug
1249+
{
1250+
debug_data_.filtered_objects = filtered_objects;
1251+
debug_data_.target_objects_on_lane = target_objects_on_lane;
1252+
debug_data_.ego_predicted_path = ego_predicted_path;
1253+
}
12491254

12501255
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
12511256
pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane,
@@ -1373,19 +1378,23 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
13731378
}
13741379
}
13751380

1376-
void StartPlannerModule::updateDrivableLanes()
1381+
void StartPlannerModule::updateDepartureCheckLanes()
13771382
{
1378-
const auto drivable_lanes = createDrivableLanes();
1383+
const auto departure_check_lanes = createDepartureCheckLanes();
13791384
for (auto & planner : start_planners_) {
13801385
auto shift_pull_out = std::dynamic_pointer_cast<ShiftPullOut>(planner);
13811386

13821387
if (shift_pull_out) {
1383-
shift_pull_out->setDrivableLanes(drivable_lanes);
1388+
shift_pull_out->setDepartureCheckLanes(departure_check_lanes);
13841389
}
13851390
}
1391+
// debug
1392+
{
1393+
debug_data_.departure_check_lanes = departure_check_lanes;
1394+
}
13861395
}
13871396

1388-
lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
1397+
lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes() const
13891398
{
13901399
const double backward_path_length =
13911400
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
@@ -1404,13 +1413,14 @@ lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
14041413
[this](const auto & pull_out_lane) {
14051414
return planner_data_->route_handler->isShoulderLanelet(pull_out_lane);
14061415
});
1407-
const auto drivable_lanes = utils::transformToLanelets(
1416+
const auto departure_check_lanes = utils::transformToLanelets(
14081417
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes));
1409-
return drivable_lanes;
1418+
return departure_check_lanes;
14101419
}
14111420

14121421
void StartPlannerModule::setDebugData()
14131422
{
1423+
using lanelet::visualization::laneletsAsTriangleMarkerArray;
14141424
using marker_utils::addFootprintMarker;
14151425
using marker_utils::createFootprintMarkerArray;
14161426
using marker_utils::createObjectsMarkerArray;
@@ -1425,6 +1435,12 @@ void StartPlannerModule::setDebugData()
14251435
using tier4_autoware_utils::createMarkerScale;
14261436
using visualization_msgs::msg::Marker;
14271437

1438+
const auto red_color = createMarkerColor(1.0, 0.0, 0.0, 0.999);
1439+
const auto cyan_color = createMarkerColor(0.0, 1.0, 1.0, 0.2);
1440+
const auto pink_color = createMarkerColor(1.0, 0.5, 0.5, 0.35);
1441+
const auto purple_color = createMarkerColor(1.0, 0.0, 1.0, 0.99);
1442+
const auto white_color = createMarkerColor(1.0, 1.0, 1.0, 0.99);
1443+
14281444
const auto life_time = rclcpp::Duration::from_seconds(1.5);
14291445
auto add = [&](MarkerArray added) {
14301446
for (auto & marker : added.markers) {
@@ -1456,10 +1472,9 @@ void StartPlannerModule::setDebugData()
14561472
if (collision_check_end_pose) {
14571473
add(createPoseMarkerArray(
14581474
*collision_check_end_pose, "static_collision_check_end_pose", 0, 1.0, 0.0, 0.0));
1459-
auto marker = tier4_autoware_utils::createDefaultMarker(
1475+
auto marker = createDefaultMarker(
14601476
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "static_collision_check_end_polygon", 0,
1461-
Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1),
1462-
tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999));
1477+
Marker::LINE_LIST, createMarkerScale(0.1, 0.1, 0.1), red_color);
14631478
const auto footprint = transformVector(
14641479
local_footprint, tier4_autoware_utils::pose2transform(*collision_check_end_pose));
14651480
const double ego_z = planner_data_->self_odometry->pose.pose.position.z;
@@ -1479,13 +1494,13 @@ void StartPlannerModule::setDebugData()
14791494
{
14801495
MarkerArray start_pose_footprint_marker_array{};
14811496
MarkerArray start_pose_text_marker_array{};
1482-
const auto purple = createMarkerColor(1.0, 0.0, 1.0, 0.99);
14831497
Marker footprint_marker = createDefaultMarker(
14841498
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates", 0, Marker::LINE_STRIP,
1485-
createMarkerScale(0.2, 0.2, 0.2), purple);
1499+
createMarkerScale(0.2, 0.2, 0.2), purple_color);
14861500
Marker text_marker = createDefaultMarker(
14871501
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates_idx", 0,
1488-
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple);
1502+
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3),
1503+
purple_color);
14891504
footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14901505
text_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14911506
for (size_t i = 0; i < debug_data_.start_pose_candidates.size(); ++i) {
@@ -1506,10 +1521,9 @@ void StartPlannerModule::setDebugData()
15061521
// visualize the footprint from pull_out_start pose to pull_out_end pose along the path
15071522
{
15081523
MarkerArray pull_out_path_footprint_marker_array{};
1509-
const auto pink = createMarkerColor(1.0, 0.0, 1.0, 0.99);
15101524
Marker pull_out_path_footprint_marker = createDefaultMarker(
15111525
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "shift_path_footprint", 0, Marker::LINE_STRIP,
1512-
createMarkerScale(0.2, 0.2, 0.2), pink);
1526+
createMarkerScale(0.2, 0.2, 0.2), pink_color);
15131527
pull_out_path_footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
15141528
PathWithLaneId path_shift_start_to_end{};
15151529
const auto shift_path = status_.pull_out_path.partial_paths.front();
@@ -1567,8 +1581,7 @@ void StartPlannerModule::setDebugData()
15671581
const auto header = planner_data_->route_handler->getRouteHeader();
15681582
{
15691583
visualization_msgs::msg::MarkerArray planner_type_marker_array{};
1570-
const auto color = status_.found_pull_out_path ? createMarkerColor(1.0, 1.0, 1.0, 0.99)
1571-
: createMarkerColor(1.0, 0.0, 0.0, 0.99);
1584+
const auto color = status_.found_pull_out_path ? white_color : red_color;
15721585
auto marker = createDefaultMarker(
15731586
header.frame_id, header.stamp, "planner_type", 0,
15741587
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color);
@@ -1583,6 +1596,15 @@ void StartPlannerModule::setDebugData()
15831596
planner_type_marker_array.markers.push_back(marker);
15841597
add(planner_type_marker_array);
15851598
}
1599+
1600+
add(laneletsAsTriangleMarkerArray(
1601+
"departure_check_lanes_for_shift_pull_out_path", debug_data_.departure_check_lanes,
1602+
cyan_color));
1603+
1604+
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
1605+
planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
1606+
add(laneletsAsTriangleMarkerArray(
1607+
"pull_out_lanes_for_static_objects_collision_check", pull_out_lanes, pink_color));
15861608
}
15871609

15881610
void StartPlannerModule::logPullOutStatus(rclcpp::Logger::Level log_level) const

0 commit comments

Comments
 (0)