24
24
#include < lanelet2_extension/utility/message_conversion.hpp>
25
25
#include < lanelet2_extension/utility/query.hpp>
26
26
#include < lanelet2_extension/utility/utilities.hpp>
27
+ #include < lanelet2_extension/visualization/visualization.hpp>
27
28
#include < magic_enum.hpp>
28
29
#include < rclcpp/rclcpp.hpp>
29
30
@@ -137,7 +138,7 @@ void StartPlannerModule::initVariables()
137
138
debug_marker_.markers .clear ();
138
139
initializeSafetyCheckParameters ();
139
140
initializeCollisionCheckDebugMap (debug_data_.collision_check );
140
- updateDrivableLanes ();
141
+ updateDepartureCheckLanes ();
141
142
}
142
143
143
144
void StartPlannerModule::updateEgoPredictedPathParams (
@@ -597,7 +598,7 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval()
597
598
void StartPlannerModule::resetStatus ()
598
599
{
599
600
status_ = PullOutStatus{};
600
- updateDrivableLanes ();
601
+ updateDepartureCheckLanes ();
601
602
}
602
603
603
604
void StartPlannerModule::incrementPathIndex ()
@@ -1244,8 +1245,12 @@ bool StartPlannerModule::isSafePath() const
1244
1245
const double hysteresis_factor =
1245
1246
status_.is_safe_dynamic_objects ? 1.0 : safety_check_params_->hysteresis_factor_expand_rate ;
1246
1247
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
+ }
1249
1254
1250
1255
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS (
1251
1256
pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane ,
@@ -1373,19 +1378,23 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
1373
1378
}
1374
1379
}
1375
1380
1376
- void StartPlannerModule::updateDrivableLanes ()
1381
+ void StartPlannerModule::updateDepartureCheckLanes ()
1377
1382
{
1378
- const auto drivable_lanes = createDrivableLanes ();
1383
+ const auto departure_check_lanes = createDepartureCheckLanes ();
1379
1384
for (auto & planner : start_planners_) {
1380
1385
auto shift_pull_out = std::dynamic_pointer_cast<ShiftPullOut>(planner);
1381
1386
1382
1387
if (shift_pull_out) {
1383
- shift_pull_out->setDrivableLanes (drivable_lanes );
1388
+ shift_pull_out->setDepartureCheckLanes (departure_check_lanes );
1384
1389
}
1385
1390
}
1391
+ // debug
1392
+ {
1393
+ debug_data_.departure_check_lanes = departure_check_lanes;
1394
+ }
1386
1395
}
1387
1396
1388
- lanelet::ConstLanelets StartPlannerModule::createDrivableLanes () const
1397
+ lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes () const
1389
1398
{
1390
1399
const double backward_path_length =
1391
1400
planner_data_->parameters .backward_path_length + parameters_->max_back_distance ;
@@ -1404,13 +1413,14 @@ lanelet::ConstLanelets StartPlannerModule::createDrivableLanes() const
1404
1413
[this ](const auto & pull_out_lane) {
1405
1414
return planner_data_->route_handler ->isShoulderLanelet (pull_out_lane);
1406
1415
});
1407
- const auto drivable_lanes = utils::transformToLanelets (
1416
+ const auto departure_check_lanes = utils::transformToLanelets (
1408
1417
utils::generateDrivableLanesWithShoulderLanes (road_lanes, shoulder_lanes));
1409
- return drivable_lanes ;
1418
+ return departure_check_lanes ;
1410
1419
}
1411
1420
1412
1421
void StartPlannerModule::setDebugData ()
1413
1422
{
1423
+ using lanelet::visualization::laneletsAsTriangleMarkerArray;
1414
1424
using marker_utils::addFootprintMarker;
1415
1425
using marker_utils::createFootprintMarkerArray;
1416
1426
using marker_utils::createObjectsMarkerArray;
@@ -1425,6 +1435,12 @@ void StartPlannerModule::setDebugData()
1425
1435
using tier4_autoware_utils::createMarkerScale;
1426
1436
using visualization_msgs::msg::Marker;
1427
1437
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
+
1428
1444
const auto life_time = rclcpp::Duration::from_seconds (1.5 );
1429
1445
auto add = [&](MarkerArray added) {
1430
1446
for (auto & marker : added.markers ) {
@@ -1456,10 +1472,9 @@ void StartPlannerModule::setDebugData()
1456
1472
if (collision_check_end_pose) {
1457
1473
add (createPoseMarkerArray (
1458
1474
*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 (
1460
1476
" 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);
1463
1478
const auto footprint = transformVector (
1464
1479
local_footprint, tier4_autoware_utils::pose2transform (*collision_check_end_pose));
1465
1480
const double ego_z = planner_data_->self_odometry ->pose .pose .position .z ;
@@ -1479,13 +1494,13 @@ void StartPlannerModule::setDebugData()
1479
1494
{
1480
1495
MarkerArray start_pose_footprint_marker_array{};
1481
1496
MarkerArray start_pose_text_marker_array{};
1482
- const auto purple = createMarkerColor (1.0 , 0.0 , 1.0 , 0.99 );
1483
1497
Marker footprint_marker = createDefaultMarker (
1484
1498
" 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 );
1486
1500
Marker text_marker = createDefaultMarker (
1487
1501
" 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);
1489
1504
footprint_marker.lifetime = rclcpp::Duration::from_seconds (1.5 );
1490
1505
text_marker.lifetime = rclcpp::Duration::from_seconds (1.5 );
1491
1506
for (size_t i = 0 ; i < debug_data_.start_pose_candidates .size (); ++i) {
@@ -1506,10 +1521,9 @@ void StartPlannerModule::setDebugData()
1506
1521
// visualize the footprint from pull_out_start pose to pull_out_end pose along the path
1507
1522
{
1508
1523
MarkerArray pull_out_path_footprint_marker_array{};
1509
- const auto pink = createMarkerColor (1.0 , 0.0 , 1.0 , 0.99 );
1510
1524
Marker pull_out_path_footprint_marker = createDefaultMarker (
1511
1525
" 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 );
1513
1527
pull_out_path_footprint_marker.lifetime = rclcpp::Duration::from_seconds (1.5 );
1514
1528
PathWithLaneId path_shift_start_to_end{};
1515
1529
const auto shift_path = status_.pull_out_path .partial_paths .front ();
@@ -1567,8 +1581,7 @@ void StartPlannerModule::setDebugData()
1567
1581
const auto header = planner_data_->route_handler ->getRouteHeader ();
1568
1582
{
1569
1583
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;
1572
1585
auto marker = createDefaultMarker (
1573
1586
header.frame_id , header.stamp , " planner_type" , 0 ,
1574
1587
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale (0.0 , 0.0 , 1.0 ), color);
@@ -1583,6 +1596,15 @@ void StartPlannerModule::setDebugData()
1583
1596
planner_type_marker_array.markers .push_back (marker);
1584
1597
add (planner_type_marker_array);
1585
1598
}
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));
1586
1608
}
1587
1609
1588
1610
void StartPlannerModule::logPullOutStatus (rclcpp::Logger::Level log_level) const
0 commit comments