@@ -236,90 +236,6 @@ MarkerArray createLaneletsAreaMarkerArray(
236
236
return msg;
237
237
}
238
238
239
- MarkerArray createFurthestLineStringMarkerArray (const lanelet::ConstLineStrings3d & linestrings)
240
- {
241
- if (linestrings.empty ()) {
242
- return MarkerArray ();
243
- }
244
-
245
- Marker marker = createDefaultMarker (
246
- " map" , rclcpp::Clock{RCL_ROS_TIME}.now (), " shared_linestring_lanelets" , 0L , Marker::LINE_STRIP,
247
- createMarkerScale (0.3 , 0.0 , 0.0 ), createMarkerColor (0.996 , 0.658 , 0.466 , 0.999 ));
248
- marker.pose .orientation = tier4_autoware_utils::createMarkerOrientation (0 , 0 , 0 , 1.0 );
249
-
250
- const auto reserve_size = linestrings.size () / 2 ;
251
- lanelet::ConstLineStrings3d lefts;
252
- lanelet::ConstLineStrings3d rights;
253
- lefts.reserve (reserve_size);
254
- rights.reserve (reserve_size);
255
-
256
- size_t total_marker_reserve_size{0 };
257
- for (size_t idx = 1 ; idx < linestrings.size (); idx += 2 ) {
258
- rights.emplace_back (linestrings.at (idx - 1 ));
259
- lefts.emplace_back (linestrings.at (idx));
260
-
261
- for (const auto & ls : linestrings.at (idx - 1 ).basicLineString ()) {
262
- total_marker_reserve_size += ls.size ();
263
- }
264
- for (const auto & ls : linestrings.at (idx).basicLineString ()) {
265
- total_marker_reserve_size += ls.size ();
266
- }
267
- }
268
-
269
- if (!total_marker_reserve_size) {
270
- marker.points .reserve (total_marker_reserve_size);
271
- }
272
-
273
- const auto & first_ls = lefts.front ().basicLineString ();
274
- for (const auto & ls : first_ls) {
275
- marker.points .push_back (createPoint (ls.x (), ls.y (), ls.z ()));
276
- }
277
-
278
- for (auto idx = lefts.cbegin () + 1 ; idx != lefts.cend (); ++idx) {
279
- Point front = createPoint (
280
- idx->basicLineString ().front ().x (), idx->basicLineString ().front ().y (),
281
- idx->basicLineString ().front ().z ());
282
- Point front_inverted = createPoint (
283
- idx->invert ().basicLineString ().front ().x (), idx->invert ().basicLineString ().front ().y (),
284
- idx->invert ().basicLineString ().front ().z ());
285
-
286
- const auto & marker_back = marker.points .back ();
287
- const bool isFrontNear = tier4_autoware_utils::calcDistance2d (marker_back, front) <
288
- tier4_autoware_utils::calcDistance2d (marker_back, front_inverted);
289
- const auto & left_ls = (isFrontNear) ? idx->basicLineString () : idx->invert ().basicLineString ();
290
- for (const auto & left_l : left_ls) {
291
- marker.points .push_back (createPoint (left_l.x (), left_l.y (), left_l.z ()));
292
- }
293
- }
294
-
295
- for (auto idx = rights.crbegin (); idx != rights.crend (); ++idx) {
296
- Point front = createPoint (
297
- idx->basicLineString ().front ().x (), idx->basicLineString ().front ().y (),
298
- idx->basicLineString ().front ().z ());
299
- Point front_inverted = createPoint (
300
- idx->invert ().basicLineString ().front ().x (), idx->invert ().basicLineString ().front ().y (),
301
- idx->invert ().basicLineString ().front ().z ());
302
-
303
- const auto & marker_back = marker.points .back ();
304
- const bool isFrontFurther = tier4_autoware_utils::calcDistance2d (marker_back, front) >
305
- tier4_autoware_utils::calcDistance2d (marker_back, front_inverted);
306
- const auto & right_ls =
307
- (isFrontFurther) ? idx->basicLineString () : idx->invert ().basicLineString ();
308
- for (auto ls = right_ls.crbegin (); ls != right_ls.crend (); ++ls) {
309
- marker.points .push_back (createPoint (ls->x (), ls->y (), ls->z ()));
310
- }
311
- }
312
-
313
- if (!marker.points .empty ()) {
314
- marker.points .push_back (marker.points .front ());
315
- }
316
-
317
- MarkerArray msg;
318
-
319
- msg.markers .push_back (marker);
320
- return msg;
321
- }
322
-
323
239
MarkerArray createPolygonMarkerArray (
324
240
const Polygon & polygon, std::string && ns, const int64_t & lane_id, const float & r,
325
241
const float & g, const float & b, const float & w)
0 commit comments