31
31
#include < string>
32
32
#include < vector>
33
33
34
- namespace behavior_velocity_planner
35
- {
36
34
namespace
37
35
{
38
36
using tier4_autoware_utils::appendMarkerArray;
39
37
using tier4_autoware_utils::createMarkerColor;
40
38
using tier4_autoware_utils::createMarkerOrientation;
41
39
using tier4_autoware_utils::createMarkerScale;
42
40
43
- static visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray (
41
+ visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray (
44
42
const std::vector<lanelet::CompoundPolygon3d> & polygons, const std::string & ns,
45
43
const int64_t lane_id, const double r, const double g, const double b)
46
44
{
47
45
visualization_msgs::msg::MarkerArray msg;
48
46
49
47
int32_t i = 0 ;
50
- int32_t uid = planning_utils::bitShift (lane_id);
48
+ int32_t uid = behavior_velocity_planner:: planning_utils::bitShift (lane_id);
51
49
for (const auto & polygon : polygons) {
52
50
visualization_msgs::msg::Marker marker{};
53
51
marker.header .frame_id = " map" ;
@@ -158,8 +156,59 @@ visualization_msgs::msg::MarkerArray createLineMarkerArray(
158
156
return marker_point;
159
157
}
160
158
159
+ constexpr std::tuple<float , float , float > white ()
160
+ {
161
+ constexpr uint64_t code = 0xfdfdfd ;
162
+ constexpr float r = static_cast <int >(code >> 16 ) / 255.0 ;
163
+ constexpr float g = static_cast <int >((code << 48 ) >> 56 ) / 255.0 ;
164
+ constexpr float b = static_cast <int >((code << 56 ) >> 56 ) / 255.0 ;
165
+ return {r, g, b};
166
+ }
167
+
168
+ constexpr std::tuple<float , float , float > green ()
169
+ {
170
+ constexpr uint64_t code = 0x5fa641 ;
171
+ constexpr float r = static_cast <int >(code >> 16 ) / 255.0 ;
172
+ constexpr float g = static_cast <int >((code << 48 ) >> 56 ) / 255.0 ;
173
+ constexpr float b = static_cast <int >((code << 56 ) >> 56 ) / 255.0 ;
174
+ return {r, g, b};
175
+ }
176
+
177
+ constexpr std::tuple<float , float , float > yellow ()
178
+ {
179
+ constexpr uint64_t code = 0xebce2b ;
180
+ constexpr float r = static_cast <int >(code >> 16 ) / 255.0 ;
181
+ constexpr float g = static_cast <int >((code << 48 ) >> 56 ) / 255.0 ;
182
+ constexpr float b = static_cast <int >((code << 56 ) >> 56 ) / 255.0 ;
183
+ return {r, g, b};
184
+ }
185
+
186
+ constexpr std::tuple<float , float , float > red ()
187
+ {
188
+ constexpr uint64_t code = 0xba1c30 ;
189
+ constexpr float r = static_cast <int >(code >> 16 ) / 255.0 ;
190
+ constexpr float g = static_cast <int >((code << 48 ) >> 56 ) / 255.0 ;
191
+ constexpr float b = static_cast <int >((code << 56 ) >> 56 ) / 255.0 ;
192
+ return {r, g, b};
193
+ }
194
+
195
+ constexpr std::tuple<float , float , float > light_blue ()
196
+ {
197
+ constexpr uint64_t code = 0x96cde6 ;
198
+ constexpr float r = static_cast <int >(code >> 16 ) / 255.0 ;
199
+ constexpr float g = static_cast <int >((code << 48 ) >> 56 ) / 255.0 ;
200
+ constexpr float b = static_cast <int >((code << 56 ) >> 56 ) / 255.0 ;
201
+ return {r, g, b};
202
+ }
161
203
} // namespace
162
204
205
+ namespace behavior_velocity_planner
206
+ {
207
+ using tier4_autoware_utils::appendMarkerArray;
208
+ using tier4_autoware_utils::createMarkerColor;
209
+ using tier4_autoware_utils::createMarkerOrientation;
210
+ using tier4_autoware_utils::createMarkerScale;
211
+
163
212
visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray ()
164
213
{
165
214
visualization_msgs::msg::MarkerArray debug_marker_array;
@@ -168,37 +217,37 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
168
217
169
218
if (debug_data_.attention_area ) {
170
219
appendMarkerArray (
171
- createLaneletPolygonsMarkerArray (
220
+ :: createLaneletPolygonsMarkerArray (
172
221
debug_data_.attention_area.value(), "attention_area", lane_id_, 0.0, 1.0, 0.0),
173
222
&debug_marker_array);
174
223
}
175
224
176
225
if (debug_data_.occlusion_attention_area ) {
177
226
appendMarkerArray (
178
- createLaneletPolygonsMarkerArray (
227
+ :: createLaneletPolygonsMarkerArray (
179
228
debug_data_.occlusion_attention_area.value(), "occlusion_attention_area", lane_id_, 0.917,
180
229
0.568, 0.596),
181
230
&debug_marker_array);
182
231
}
183
232
184
233
if (debug_data_.adjacent_area ) {
185
234
appendMarkerArray (
186
- createLaneletPolygonsMarkerArray (
235
+ :: createLaneletPolygonsMarkerArray (
187
236
debug_data_.adjacent_area.value(), "adjacent_area", lane_id_, 0.913, 0.639, 0.149),
188
237
&debug_marker_array);
189
238
}
190
239
191
240
if (debug_data_.first_attention_area ) {
192
241
appendMarkerArray (
193
- createLaneletPolygonsMarkerArray (
242
+ :: createLaneletPolygonsMarkerArray (
194
243
{debug_data_.first_attention_area .value ()}, " first_attention_area" , lane_id_, 1 , 0.647 ,
195
244
0.0 ),
196
245
&debug_marker_array, now);
197
246
}
198
247
199
248
if (debug_data_.second_attention_area ) {
200
249
appendMarkerArray (
201
- createLaneletPolygonsMarkerArray (
250
+ :: createLaneletPolygonsMarkerArray (
202
251
{debug_data_.second_attention_area .value ()}, " second_attention_area" , lane_id_, 1 , 0.647 ,
203
252
0.0 ),
204
253
&debug_marker_array, now);
@@ -214,15 +263,15 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
214
263
215
264
if (debug_data_.yield_stuck_detect_area ) {
216
265
appendMarkerArray (
217
- createLaneletPolygonsMarkerArray (
266
+ :: createLaneletPolygonsMarkerArray (
218
267
debug_data_.yield_stuck_detect_area.value(), "yield_stuck_detect_area", lane_id_, 0.6588235,
219
268
0.34509, 0.6588235),
220
269
&debug_marker_array);
221
270
}
222
271
223
272
if (debug_data_.ego_lane ) {
224
273
appendMarkerArray (
225
- createLaneletPolygonsMarkerArray (
274
+ :: createLaneletPolygonsMarkerArray (
226
275
{debug_data_.ego_lane .value ()}, " ego_lane" , lane_id_, 1 , 0.647 , 0.0 ),
227
276
&debug_marker_array, now);
228
277
}
@@ -235,59 +284,58 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
235
284
&debug_marker_array, now);
236
285
}
237
286
238
- size_t i{0 };
239
- for (const auto & p : debug_data_.candidate_collision_object_polygons ) {
240
- appendMarkerArray (
241
- debug::createPolygonMarkerArray (
242
- p, " candidate_collision_object_polygons" , lane_id_ + i++, now, 0.3 , 0.0 , 0.0 , 0.0 , 0.5 ,
243
- 0.5 ),
244
- &debug_marker_array, now);
245
- }
246
-
287
+ static constexpr auto white = ::white ();
288
+ static constexpr auto green = ::green ();
289
+ static constexpr auto yellow = ::yellow ();
290
+ static constexpr auto red = ::red ();
291
+ static constexpr auto light_blue = ::light_blue ();
247
292
appendMarkerArray (
248
293
debug::createObjectsMarkerArray (
249
- debug_data_.conflicting_targets , " conflicting_targets" , module_id_, now, 0.99 , 0.4 , 0.0 ),
294
+ debug_data_.safe_under_traffic_control_targets , " safe_under_traffic_control_targets" ,
295
+ module_id_, now, std::get<0 >(light_blue), std::get<1 >(light_blue), std::get<2 >(light_blue)),
250
296
&debug_marker_array, now);
251
297
252
298
appendMarkerArray (
253
299
debug::createObjectsMarkerArray (
254
- debug_data_.amber_ignore_targets , " amber_ignore_targets" , module_id_, now, 0.0 , 1.0 , 0.0 ),
300
+ debug_data_.unsafe_targets , " unsafe_targets" , module_id_, now, std::get<0 >(green),
301
+ std::get<1 >(green), std::get<2 >(green)),
255
302
&debug_marker_array, now);
256
303
257
304
appendMarkerArray (
258
305
debug::createObjectsMarkerArray (
259
- debug_data_.red_overshoot_ignore_targets , " red_overshoot_ignore_targets " , module_id_, now,
260
- 0.0 , 1.0 , 0.0 ),
306
+ debug_data_.misjudge_targets , " misjudge_targets " , module_id_, now, std::get< 0 >(yellow) ,
307
+ std::get< 1 >(yellow), std::get< 2 >(yellow) ),
261
308
&debug_marker_array, now);
262
309
263
310
appendMarkerArray (
264
311
debug::createObjectsMarkerArray (
265
- debug_data_.stuck_targets , " stuck_targets" , module_id_, now, 0.99 , 0.99 , 0.2 ),
312
+ debug_data_.too_late_detect_targets , " too_late_detect_targets" , module_id_, now,
313
+ std::get<0 >(red), std::get<1 >(red), std::get<2 >(red)),
266
314
&debug_marker_array, now);
267
315
268
316
appendMarkerArray (
269
317
debug::createObjectsMarkerArray (
270
- debug_data_.yield_stuck_targets , " stuck_targets" , module_id_, now, 0.4 , 0.99 , 0.2 ),
318
+ debug_data_.parked_targets , " parked_targets" , module_id_, now, std::get<0 >(white),
319
+ std::get<1 >(white), std::get<2 >(white)),
271
320
&debug_marker_array, now);
272
321
273
322
appendMarkerArray (
274
323
debug::createObjectsMarkerArray (
275
- debug_data_.blocking_attention_objects , " blocking_attention_objects " , module_id_, now, 0.99 ,
276
- 0.99 , 0.6 ),
324
+ debug_data_.stuck_targets , " stuck_targets " , module_id_, now, std::get< 0 >(white) ,
325
+ std::get< 1 >(white), std::get< 2 >(white) ),
277
326
&debug_marker_array, now);
278
327
279
- /*
280
328
appendMarkerArray (
281
- createPoseMarkerArray(
282
- debug_data_.predicted_obj_pose, "predicted_obj_pose", module_id_, 0.7, 0.85, 0.9),
329
+ debug::createObjectsMarkerArray (
330
+ debug_data_.yield_stuck_targets , " yield_stuck_targets" , module_id_, now, std::get<0 >(white),
331
+ std::get<1 >(white), std::get<2 >(white)),
283
332
&debug_marker_array, now);
284
- */
285
333
286
334
if (debug_data_.first_pass_judge_wall_pose ) {
287
335
const double r = debug_data_.passed_first_pass_judge ? 1.0 : 0.0 ;
288
336
const double g = debug_data_.passed_first_pass_judge ? 0.0 : 1.0 ;
289
337
appendMarkerArray (
290
- createPoseMarkerArray (
338
+ :: createPoseMarkerArray (
291
339
debug_data_.first_pass_judge_wall_pose.value(), "first_pass_judge_wall_pose", module_id_, r,
292
340
g, 0.0),
293
341
&debug_marker_array, now);
@@ -297,7 +345,7 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
297
345
const double r = debug_data_.passed_second_pass_judge ? 1.0 : 0.0 ;
298
346
const double g = debug_data_.passed_second_pass_judge ? 0.0 : 1.0 ;
299
347
appendMarkerArray (
300
- createPoseMarkerArray (
348
+ :: createPoseMarkerArray (
301
349
debug_data_.second_pass_judge_wall_pose.value(), "second_pass_judge_wall_pose", module_id_,
302
350
r, g, 0.0),
303
351
&debug_marker_array, now);
@@ -314,7 +362,7 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
314
362
if (debug_data_.nearest_occlusion_projection ) {
315
363
const auto [point_start, point_end] = debug_data_.nearest_occlusion_projection .value ();
316
364
appendMarkerArray (
317
- createLineMarkerArray (
365
+ :: createLineMarkerArray (
318
366
point_start, point_end, " nearest_occlusion_projection" , lane_id_, 0.5 , 0.5 , 0.0 ),
319
367
&debug_marker_array, now);
320
368
}
@@ -369,11 +417,11 @@ visualization_msgs::msg::MarkerArray MergeFromPrivateRoadModule::createDebugMark
369
417
370
418
const auto state = state_machine_.getState ();
371
419
372
- int32_t uid = planning_utils::bitShift (module_id_);
420
+ int32_t uid = behavior_velocity_planner:: planning_utils::bitShift (module_id_);
373
421
const auto now = this ->clock_ ->now ();
374
422
if (state == StateMachine::State::STOP) {
375
423
appendMarkerArray (
376
- createPoseMarkerArray (debug_data_.stop_point_pose , " stop_point_pose" , uid, 1.0 , 0.0 , 0.0 ),
424
+ :: createPoseMarkerArray (debug_data_.stop_point_pose, " stop_point_pose" , uid, 1.0 , 0.0 , 0.0 ),
377
425
&debug_marker_array, now);
378
426
}
379
427
0 commit comments