Skip to content

Commit 8187cd7

Browse files
Update shift path lane departure check
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 4c3ea87 commit 8187cd7

File tree

6 files changed

+58
-28
lines changed

6 files changed

+58
-28
lines changed

planning/behavior_path_start_planner_module/config/start_planner.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
center_line_path_interval: 1.0
1414
# shift pull out
1515
enable_shift_pull_out: true
16-
check_shift_path_lane_departure: false
16+
check_shift_path_lane_departure: true
1717
minimum_shift_pull_out_distance: 0.0
1818
deceleration_interval: 15.0
1919
lateral_jerk: 0.5

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
@@ -242,8 +242,8 @@ class StartPlannerModule : public SceneModuleInterface
242242
const std::vector<PoseWithVelocityStamped> & ego_predicted_path) const;
243243
bool isSafePath() const;
244244
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;
245-
void updateDrivableLanes();
246-
lanelet::ConstLanelets createDrivableLanes() const;
245+
void updateDepartureCheckLanes();
246+
lanelet::ConstLanelets createDepartureCheckLanes() const;
247247

248248
// check if the goal is located behind the ego in the same route segment.
249249
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
@@ -23,6 +23,7 @@
2323

2424
#include <lanelet2_extension/utility/query.hpp>
2525
#include <lanelet2_extension/utility/utilities.hpp>
26+
#include <lanelet2_extension/visualization/visualization.hpp>
2627
#include <magic_enum.hpp>
2728
#include <rclcpp/rclcpp.hpp>
2829

@@ -136,7 +137,7 @@ void StartPlannerModule::initVariables()
136137
debug_marker_.markers.clear();
137138
initializeSafetyCheckParameters();
138139
initializeCollisionCheckDebugMap(debug_data_.collision_check);
139-
updateDrivableLanes();
140+
updateDepartureCheckLanes();
140141
}
141142

142143
void StartPlannerModule::updateEgoPredictedPathParams(
@@ -564,7 +565,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
564565
void StartPlannerModule::resetStatus()
565566
{
566567
status_ = PullOutStatus{};
567-
updateDrivableLanes();
568+
updateDepartureCheckLanes();
568569
}
569570

570571
void StartPlannerModule::incrementPathIndex()
@@ -1202,8 +1203,12 @@ bool StartPlannerModule::isSafePath() const
12021203
const double hysteresis_factor =
12031204
status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate;
12041205

1205-
behavior_path_planner::updateSafetyCheckDebugData(
1206-
debug_data_, filtered_objects, target_objects_on_lane, ego_predicted_path);
1206+
// debug
1207+
{
1208+
debug_data_.filtered_objects = filtered_objects;
1209+
debug_data_.target_objects_on_lane = target_objects_on_lane;
1210+
debug_data_.ego_predicted_path = ego_predicted_path;
1211+
}
12071212

12081213
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
12091214
pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane,
@@ -1331,19 +1336,23 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
13311336
}
13321337
}
13331338

1334-
void StartPlannerModule::updateDrivableLanes()
1339+
void StartPlannerModule::updateDepartureCheckLanes()
13351340
{
1336-
const auto drivable_lanes = createDrivableLanes();
1341+
const auto departure_check_lanes = createDepartureCheckLanes();
13371342
for (auto & planner : start_planners_) {
13381343
auto shift_pull_out = std::dynamic_pointer_cast<ShiftPullOut>(planner);
13391344

13401345
if (shift_pull_out) {
1341-
shift_pull_out->setDrivableLanes(drivable_lanes);
1346+
shift_pull_out->setDepartureCheckLanes(departure_check_lanes);
13421347
}
13431348
}
1349+
// debug
1350+
{
1351+
debug_data_.departure_check_lanes = departure_check_lanes;
1352+
}
13441353
}
13451354

1346-
lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
1355+
lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes() const
13471356
{
13481357
const double backward_path_length =
13491358
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
@@ -1362,13 +1371,14 @@ lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
13621371
[this](const auto & pull_out_lane) {
13631372
return planner_data_->route_handler->isShoulderLanelet(pull_out_lane);
13641373
});
1365-
const auto drivable_lanes = utils::transformToLanelets(
1374+
const auto departure_check_lanes = utils::transformToLanelets(
13661375
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes));
1367-
return drivable_lanes;
1376+
return departure_check_lanes;
13681377
}
13691378

13701379
void StartPlannerModule::setDebugData()
13711380
{
1381+
using lanelet::visualization::laneletsAsTriangleMarkerArray;
13721382
using marker_utils::addFootprintMarker;
13731383
using marker_utils::createFootprintMarkerArray;
13741384
using marker_utils::createObjectsMarkerArray;
@@ -1383,6 +1393,12 @@ void StartPlannerModule::setDebugData()
13831393
using tier4_autoware_utils::createMarkerScale;
13841394
using visualization_msgs::msg::Marker;
13851395

1396+
const auto red_color = createMarkerColor(1.0, 0.0, 0.0, 0.999);
1397+
const auto cyan_color = createMarkerColor(0.0, 1.0, 1.0, 0.2);
1398+
const auto pink_color = createMarkerColor(1.0, 0.5, 0.5, 0.35);
1399+
const auto purple_color = createMarkerColor(1.0, 0.0, 1.0, 0.99);
1400+
const auto white_color = createMarkerColor(1.0, 1.0, 1.0, 0.99);
1401+
13861402
const auto life_time = rclcpp::Duration::from_seconds(1.5);
13871403
auto add = [&](MarkerArray added) {
13881404
for (auto & marker : added.markers) {
@@ -1409,10 +1425,9 @@ void StartPlannerModule::setDebugData()
14091425
if (collision_check_end_pose) {
14101426
add(createPoseMarkerArray(
14111427
*collision_check_end_pose, "static_collision_check_end_pose", 0, 1.0, 0.0, 0.0));
1412-
auto marker = tier4_autoware_utils::createDefaultMarker(
1428+
auto marker = createDefaultMarker(
14131429
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "static_collision_check_end_polygon", 0,
1414-
Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1),
1415-
tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999));
1430+
Marker::LINE_LIST, createMarkerScale(0.1, 0.1, 0.1), red_color);
14161431
const auto footprint = transformVector(
14171432
local_footprint, tier4_autoware_utils::pose2transform(*collision_check_end_pose));
14181433
const double ego_z = planner_data_->self_odometry->pose.pose.position.z;
@@ -1432,13 +1447,13 @@ void StartPlannerModule::setDebugData()
14321447
{
14331448
MarkerArray start_pose_footprint_marker_array{};
14341449
MarkerArray start_pose_text_marker_array{};
1435-
const auto purple = createMarkerColor(1.0, 0.0, 1.0, 0.99);
14361450
Marker footprint_marker = createDefaultMarker(
14371451
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates", 0, Marker::LINE_STRIP,
1438-
createMarkerScale(0.2, 0.2, 0.2), purple);
1452+
createMarkerScale(0.2, 0.2, 0.2), purple_color);
14391453
Marker text_marker = createDefaultMarker(
14401454
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "start_pose_candidates_idx", 0,
1441-
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3), purple);
1455+
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.3, 0.3, 0.3),
1456+
purple_color);
14421457
footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14431458
text_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14441459
for (size_t i = 0; i < debug_data_.start_pose_candidates.size(); ++i) {
@@ -1459,10 +1474,9 @@ void StartPlannerModule::setDebugData()
14591474
// visualize the footprint from pull_out_start pose to pull_out_end pose along the path
14601475
{
14611476
MarkerArray pull_out_path_footprint_marker_array{};
1462-
const auto pink = createMarkerColor(1.0, 0.0, 1.0, 0.99);
14631477
Marker pull_out_path_footprint_marker = createDefaultMarker(
14641478
"map", rclcpp::Clock{RCL_ROS_TIME}.now(), "shift_path_footprint", 0, Marker::LINE_STRIP,
1465-
createMarkerScale(0.2, 0.2, 0.2), pink);
1479+
createMarkerScale(0.2, 0.2, 0.2), pink_color);
14661480
pull_out_path_footprint_marker.lifetime = rclcpp::Duration::from_seconds(1.5);
14671481
PathWithLaneId path_shift_start_to_end{};
14681482
const auto shift_path = status_.pull_out_path.partial_paths.front();
@@ -1520,8 +1534,7 @@ void StartPlannerModule::setDebugData()
15201534
const auto header = planner_data_->route_handler->getRouteHeader();
15211535
{
15221536
visualization_msgs::msg::MarkerArray planner_type_marker_array{};
1523-
const auto color = status_.found_pull_out_path ? createMarkerColor(1.0, 1.0, 1.0, 0.99)
1524-
: createMarkerColor(1.0, 0.0, 0.0, 0.99);
1537+
const auto color = status_.found_pull_out_path ? white_color : red_color;
15251538
auto marker = createDefaultMarker(
15261539
header.frame_id, header.stamp, "planner_type", 0,
15271540
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color);
@@ -1536,6 +1549,15 @@ void StartPlannerModule::setDebugData()
15361549
planner_type_marker_array.markers.push_back(marker);
15371550
add(planner_type_marker_array);
15381551
}
1552+
1553+
add(laneletsAsTriangleMarkerArray(
1554+
"departure_check_lanes_for_shift_pull_out_path", debug_data_.departure_check_lanes,
1555+
cyan_color));
1556+
1557+
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
1558+
planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
1559+
add(laneletsAsTriangleMarkerArray(
1560+
"pull_out_lanes_for_static_objects_collision_check", pull_out_lanes, pink_color));
15391561
}
15401562

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

0 commit comments

Comments
 (0)