@@ -1283,6 +1283,7 @@ void StartPlannerModule::setDebugData() const
1283
1283
using tier4_autoware_utils::createDefaultMarker;
1284
1284
using tier4_autoware_utils::createMarkerColor;
1285
1285
using tier4_autoware_utils::createMarkerScale;
1286
+ using visualization_msgs::msg::Marker;
1286
1287
1287
1288
const auto life_time = rclcpp::Duration::from_seconds (1.5 );
1288
1289
auto add = [&](MarkerArray added) {
@@ -1299,6 +1300,35 @@ void StartPlannerModule::setDebugData() const
1299
1300
add (createPathMarkerArray (getFullPath (), " full_path" , 0 , 0.0 , 0.5 , 0.9 ));
1300
1301
add (createPathMarkerArray (status_.backward_path , " backward_driving_path" , 0 , 0.0 , 0.9 , 0.0 ));
1301
1302
1303
+ // visualize collision_check_end_pose and footprint
1304
+ {
1305
+ const auto local_footprint = createVehicleFootprint (vehicle_info_);
1306
+ const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose (
1307
+ getFullPath ().points , status_.pull_out_path .end_pose .position ,
1308
+ parameters_->collision_check_distance_from_end );
1309
+ if (collision_check_end_pose) {
1310
+ add (createPoseMarkerArray (
1311
+ *collision_check_end_pose, " static_collision_check_end_pose" , 0 , 1.0 , 0.0 , 0.0 ));
1312
+ auto marker = tier4_autoware_utils::createDefaultMarker (
1313
+ " map" , rclcpp::Clock{RCL_ROS_TIME}.now (), " static_collision_check_end_polygon" , 0 ,
1314
+ Marker::LINE_LIST, tier4_autoware_utils::createMarkerScale (0.1 , 0.1 , 0.1 ),
1315
+ tier4_autoware_utils::createMarkerColor (1.0 , 0.0 , 0.0 , 0.999 ));
1316
+ const auto footprint = transformVector (
1317
+ local_footprint, tier4_autoware_utils::pose2transform (*collision_check_end_pose));
1318
+ const double ego_z = planner_data_->self_odometry ->pose .pose .position .z ;
1319
+ for (size_t i = 0 ; i < footprint.size (); i++) {
1320
+ const auto & current_point = footprint.at (i);
1321
+ const auto & next_point = footprint.at ((i + 1 ) % footprint.size ());
1322
+ marker.points .push_back (
1323
+ tier4_autoware_utils::createPoint (current_point.x (), current_point.y (), ego_z));
1324
+ marker.points .push_back (
1325
+ tier4_autoware_utils::createPoint (next_point.x (), next_point.y (), ego_z));
1326
+ }
1327
+ marker.lifetime = life_time;
1328
+ debug_marker_.markers .push_back (marker);
1329
+ }
1330
+ }
1331
+
1302
1332
// safety check
1303
1333
if (parameters_->safety_check_params .enable_safety_check ) {
1304
1334
if (start_planner_data_.ego_predicted_path .size () > 0 ) {
0 commit comments