CARLA
 
载入中...
搜索中...
未找到
MeshFactory.cpp
浏览该文件的文档.
1// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma
2// de Barcelona (UAB).
3//
4// This work is licensed under the terms of the MIT license.
5// For a copy, see <https://opensource.org/licenses/MIT>.
6
8
9#include <vector>
10
11#include <carla/geom/Vector3D.h>
12#include <carla/geom/Rtree.h>
15#include <carla/road/Map.h>
17
18namespace carla {
19namespace geom {
20
22 road_param.resolution = static_cast<float>(params.vertex_distance);
23 road_param.max_road_len = static_cast<float>(params.max_road_length);
24 road_param.extra_lane_width = static_cast<float>(params.additional_width);
25 road_param.wall_height = static_cast<float>(params.wall_height);
27 }
28
29 /// We use this epsilon to shift the waypoints away from the edges of the lane
30 /// sections to avoid floating point precision errors.
31 static constexpr double EPSILON = 10.0 * std::numeric_limits<double>::epsilon();
32 static constexpr double MESH_EPSILON = 50.0 * std::numeric_limits<double>::epsilon();
33
34 std::unique_ptr<Mesh> MeshFactory::Generate(const road::Road &road) const {
35 Mesh out_mesh;
36 for (auto &&lane_section : road.GetLaneSections()) {
37 out_mesh += *Generate(lane_section);
38 }
39 return std::make_unique<Mesh>(out_mesh);
40 }
41
42 std::unique_ptr<Mesh> MeshFactory::Generate(const road::LaneSection &lane_section) const {
43 Mesh out_mesh;
44 for (auto &&lane_pair : lane_section.GetLanes()) {
45 out_mesh += *Generate(lane_pair.second);
46 }
47 return std::make_unique<Mesh>(out_mesh);
48 }
49
50 std::unique_ptr<Mesh> MeshFactory::Generate(const road::Lane &lane) const {
51 const double s_start = lane.GetDistance() + EPSILON;
52 const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
53 return Generate(lane, s_start, s_end);
54 }
55
56 std::unique_ptr<Mesh> MeshFactory::GenerateTesselated(const road::Lane& lane) const {
57 const double s_start = lane.GetDistance() + EPSILON;
58 const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
59 return GenerateTesselated(lane, s_start, s_end);
60 }
61
62 std::unique_ptr<Mesh> MeshFactory::Generate(
63 const road::Lane &lane, const double s_start, const double s_end) const {
65 DEBUG_ASSERT(s_start >= 0.0);
66 DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
67 DEBUG_ASSERT(s_end >= EPSILON);
68 DEBUG_ASSERT(s_start < s_end);
69 // The lane with lane_id 0 have no physical representation in OpenDRIVE
70 Mesh out_mesh;
71 if (lane.GetId() == 0) {
72 return std::make_unique<Mesh>(out_mesh);
73 }
74 double s_current = s_start;
75
76 std::vector<geom::Vector3D> vertices;
77 if (lane.IsStraight()) {
78 // Mesh optimization: If the lane is straight just add vertices at the
79 // begining and at the end of it
80 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
81 vertices.push_back(edges.first);
82 vertices.push_back(edges.second);
83 } else {
84 // Iterate over the lane's 's' and store the vertices based on it's width
85 do {
86 // Get the location of the edges of the current lane at the current waypoint
87 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
88 vertices.push_back(edges.first);
89 vertices.push_back(edges.second);
90
91 // Update the current waypoint's "s"
92 s_current += road_param.resolution;
93 } while(s_current < s_end);
94 }
95
96 // This ensures the mesh is constant and have no gaps between roads,
97 // adding geometry at the very end of the lane
98 if (s_end - (s_current - road_param.resolution) > EPSILON) {
99 const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
100 vertices.push_back(edges.first);
101 vertices.push_back(edges.second);
102 }
103
104 // Add the adient material, create the strip and close the material
105 out_mesh.AddMaterial(
106 lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
107 out_mesh.AddTriangleStrip(vertices);
108 out_mesh.EndMaterial();
109 return std::make_unique<Mesh>(out_mesh);
110 }
111
112 std::unique_ptr<Mesh> MeshFactory::GenerateTesselated(
113 const road::Lane& lane, const double s_start, const double s_end) const {
115 DEBUG_ASSERT(s_start >= 0.0);
116 DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
117 DEBUG_ASSERT(s_end >= EPSILON);
118 DEBUG_ASSERT(s_start < s_end);
119 // The lane with lane_id 0 have no physical representation in OpenDRIVE
120 Mesh out_mesh;
121 if (lane.GetId() == 0) {
122 return std::make_unique<Mesh>(out_mesh);
123 }
124 double s_current = s_start;
125
126 std::vector<geom::Vector3D> vertices;
127 // Ensure minimum vertices in width are two
128 const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
129 const int segments_number = vertices_in_width - 1;
130
131 std::vector<geom::Vector2D> uvs;
132 int uvx = 0;
133 int uvy = 0;
134 // Iterate over the lane's 's' and store the vertices based on it's width
135 do {
136 // Get the location of the edges of the current lane at the current waypoint
137 std::pair<geom::Vector3D, geom::Vector3D> edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
138 const geom::Vector3D segments_size = ( edges.second - edges.first ) / segments_number;
139 geom::Vector3D current_vertex = edges.first;
140 uvx = 0;
141 for (int i = 0; i < vertices_in_width; ++i) {
142 uvs.push_back(geom::Vector2D(uvx, uvy));
143 vertices.push_back(current_vertex);
144 current_vertex = current_vertex + segments_size;
145 uvx++;
146 }
147 uvy++;
148 // Update the current waypoint's "s"
149 s_current += road_param.resolution;
150 } while (s_current < s_end);
151
152 // This ensures the mesh is constant and have no gaps between roads,
153 // adding geometry at the very end of the lane
154
155 if (s_end - (s_current - road_param.resolution) > EPSILON) {
156 std::pair<carla::geom::Vector3D, carla::geom::Vector3D> edges =
158 const geom::Vector3D segments_size = (edges.second - edges.first) / segments_number;
159 geom::Vector3D current_vertex = edges.first;
160 uvx = 0;
161 for (int i = 0; i < vertices_in_width; ++i)
162 {
163 uvs.push_back(geom::Vector2D(uvx, uvy));
164 vertices.push_back(current_vertex);
165 current_vertex = current_vertex + segments_size;
166 uvx++;
167 }
168 }
169 out_mesh.AddVertices(vertices);
170 out_mesh.AddUVs(uvs);
171
172 // Add the adient material, create the strip and close the material
173 out_mesh.AddMaterial(
174 lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
175
176 const size_t number_of_rows = (vertices.size() / vertices_in_width);
177
178 for (size_t i = 0; i < (number_of_rows - 1); ++i) {
179 for (size_t j = 0; j < vertices_in_width - 1; ++j) {
180 out_mesh.AddIndex( j + ( i * vertices_in_width ) + 1);
181 out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
182 out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
183
184 out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
185 out_mesh.AddIndex( ( j + 1 ) + ( ( i + 1 ) * vertices_in_width ) + 1);
186 out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
187 }
188 }
189 out_mesh.EndMaterial();
190 return std::make_unique<Mesh>(out_mesh);
191 }
192
193
195 const road::LaneSection &lane_section,
196 std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& result) const {
197
198 const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
199 std::vector<size_t> redirections;
200 for (auto &&lane_pair : lane_section.GetLanes()) {
201 auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
202 if ( it == redirections.end() ) {
203 redirections.push_back(lane_pair.first);
204 it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
205 }
206 size_t PosToAdd = it - redirections.begin();
207
208 Mesh out_mesh;
209 switch(lane_pair.second.GetType())
210 {
214 {
215 out_mesh += *GenerateTesselated(lane_pair.second);
216 break;
217 }
221 {
222 out_mesh += *GenerateSidewalk(lane_pair.second);
223 break;
224 }
225 default:
226 {
227 out_mesh += *GenerateTesselated(lane_pair.second);
228 break;
229 }
230 }
231
232 if( result[lane_pair.second.GetType()].size() <= PosToAdd ){
233 result[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(out_mesh));
234 } else {
235 uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType());
236 (result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, verticesinwidth);
237 }
238 }
239 }
240
241
242 std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::LaneSection &lane_section) const{
243 Mesh out_mesh;
244 for (auto &&lane_pair : lane_section.GetLanes()) {
245 const double s_start = lane_pair.second.GetDistance() + EPSILON;
246 const double s_end = lane_pair.second.GetDistance() + lane_pair.second.GetLength() - EPSILON;
247 out_mesh += *GenerateSidewalk(lane_pair.second, s_start, s_end);
248 }
249 return std::make_unique<Mesh>(out_mesh);
250 }
251 std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::Lane &lane) const{
252 const double s_start = lane.GetDistance() + EPSILON;
253 const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
254 return GenerateSidewalk(lane, s_start, s_end);
255 }
256 std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(
257 const road::Lane &lane, const double s_start,
258 const double s_end ) const {
259
261 DEBUG_ASSERT(s_start >= 0.0);
262 DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
263 DEBUG_ASSERT(s_end >= EPSILON);
264 DEBUG_ASSERT(s_start < s_end);
265 // The lane with lane_id 0 have no physical representation in OpenDRIVE
266 Mesh out_mesh;
267 if (lane.GetId() == 0) {
268 return std::make_unique<Mesh>(out_mesh);
269 }
270 double s_current = s_start;
271
272 std::vector<geom::Vector3D> vertices;
273 // Ensure minimum vertices in width are two
274 const int vertices_in_width = 6;
275 const int segments_number = vertices_in_width - 1;
276 std::vector<geom::Vector2D> uvs;
277 int uvy = 0;
278
279 // Iterate over the lane's 's' and store the vertices based on it's width
280 do {
281 // Get the location of the edges of the current lane at the current waypoint
282 std::pair<geom::Vector3D, geom::Vector3D> edges =
284
285 geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
286 geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
287 vertices.push_back(low_vertex_first);
288 uvs.push_back(geom::Vector2D(0, uvy));
289
290 vertices.push_back(edges.first);
291 uvs.push_back(geom::Vector2D(1, uvy));
292
293 vertices.push_back(edges.first);
294 uvs.push_back(geom::Vector2D(1, uvy));
295
296 vertices.push_back(edges.second);
297 uvs.push_back(geom::Vector2D(2, uvy));
298
299 vertices.push_back(edges.second);
300 uvs.push_back(geom::Vector2D(2, uvy));
301
302 vertices.push_back(low_vertex_second);
303 uvs.push_back(geom::Vector2D(3, uvy));
304
305 // Update the current waypoint's "s"
306 s_current += road_param.resolution;
307 uvy++;
308 } while (s_current < s_end);
309
310 // This ensures the mesh is constant and have no gaps between roads,
311 // adding geometry at the very end of the lane
312
313 if (s_end - (s_current - road_param.resolution) > EPSILON) {
314 std::pair<carla::geom::Vector3D, carla::geom::Vector3D> edges =
316
317 geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
318 geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
319
320 vertices.push_back(low_vertex_first);
321 uvs.push_back(geom::Vector2D(0, uvy));
322
323 vertices.push_back(edges.first);
324 uvs.push_back(geom::Vector2D(1, uvy));
325
326 vertices.push_back(edges.first);
327 uvs.push_back(geom::Vector2D(1, uvy));
328
329 vertices.push_back(edges.second);
330 uvs.push_back(geom::Vector2D(2, uvy));
331
332 vertices.push_back(edges.second);
333 uvs.push_back(geom::Vector2D(2, uvy));
334
335 vertices.push_back(low_vertex_second);
336 uvs.push_back(geom::Vector2D(3, uvy));
337
338 }
339
340 out_mesh.AddVertices(vertices);
341 out_mesh.AddUVs(uvs);
342 // Add the adient material, create the strip and close the material
343 out_mesh.AddMaterial(
344 lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
345
346 const int number_of_rows = (vertices.size() / vertices_in_width);
347
348 for (size_t i = 0; i < (number_of_rows - 1); ++i) {
349 for (size_t j = 0; j < vertices_in_width - 1; ++j) {
350
351 if(j == 1 || j == 3){
352 continue;
353 }
354
355 out_mesh.AddIndex( j + ( i * vertices_in_width ) + 1);
356 out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
357 out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
358
359 out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
360 out_mesh.AddIndex( ( j + 1 ) + ( ( i + 1 ) * vertices_in_width ) + 1);
361 out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
362
363 }
364 }
365 out_mesh.EndMaterial();
366 return std::make_unique<Mesh>(out_mesh);
367 }
368 std::unique_ptr<Mesh> MeshFactory::GenerateWalls(const road::LaneSection &lane_section) const {
369 Mesh out_mesh;
370
371 const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
372 1 : lane_section.GetLanes().begin()->first;
373 const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
374 -1 : lane_section.GetLanes().rbegin()->first;
375
376 for (auto &&lane_pair : lane_section.GetLanes()) {
377 const auto &lane = lane_pair.second;
378 const double s_start = lane.GetDistance() + EPSILON;
379 const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
380 if (lane.GetId() == max_lane) {
381 out_mesh += *GenerateLeftWall(lane, s_start, s_end);
382 }
383 if (lane.GetId() == min_lane) {
384 out_mesh += *GenerateRightWall(lane, s_start, s_end);
385 }
386 }
387 return std::make_unique<Mesh>(out_mesh);
388 }
389
390 std::unique_ptr<Mesh> MeshFactory::GenerateRightWall(
391 const road::Lane &lane, const double s_start, const double s_end) const {
393 DEBUG_ASSERT(s_start >= 0.0);
394 DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
395 DEBUG_ASSERT(s_end >= EPSILON);
396 DEBUG_ASSERT(s_start < s_end);
397 // The lane with lane_id 0 have no physical representation in OpenDRIVE
398 Mesh out_mesh;
399 if (lane.GetId() == 0) {
400 return std::make_unique<Mesh>(out_mesh);
401 }
402 double s_current = s_start;
403 const geom::Vector3D height_vector = geom::Vector3D(0.f, 0.f, road_param.wall_height);
404
405 std::vector<geom::Vector3D> r_vertices;
406 if (lane.IsStraight()) {
407 // Mesh optimization: If the lane is straight just add vertices at the
408 // begining and at the end of it
409 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
410 r_vertices.push_back(edges.first + height_vector);
411 r_vertices.push_back(edges.first);
412 } else {
413 // Iterate over the lane's 's' and store the vertices based on it's width
414 do {
415 // Get the location of the edges of the current lane at the current waypoint
416 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
417 r_vertices.push_back(edges.first + height_vector);
418 r_vertices.push_back(edges.first);
419
420 // Update the current waypoint's "s"
421 s_current += road_param.resolution;
422 } while(s_current < s_end);
423 }
424
425 // This ensures the mesh is constant and have no gaps between roads,
426 // adding geometry at the very end of the lane
427 if (s_end - (s_current - road_param.resolution) > EPSILON) {
428 const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
429 r_vertices.push_back(edges.first + height_vector);
430 r_vertices.push_back(edges.first);
431 }
432
433 // Add the adient material, create the strip and close the material
434 out_mesh.AddMaterial(
435 lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
436 out_mesh.AddTriangleStrip(r_vertices);
437 out_mesh.EndMaterial();
438 return std::make_unique<Mesh>(out_mesh);
439 }
440
441 std::unique_ptr<Mesh> MeshFactory::GenerateLeftWall(
442 const road::Lane &lane, const double s_start, const double s_end) const {
444 DEBUG_ASSERT(s_start >= 0.0);
445 DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
446 DEBUG_ASSERT(s_end >= EPSILON);
447 DEBUG_ASSERT(s_start < s_end);
448 // The lane with lane_id 0 have no physical representation in OpenDRIVE
449 Mesh out_mesh;
450 if (lane.GetId() == 0) {
451 return std::make_unique<Mesh>(out_mesh);
452 }
453 double s_current = s_start;
454 const geom::Vector3D height_vector = geom::Vector3D(0.f, 0.f, road_param.wall_height);
455
456 std::vector<geom::Vector3D> l_vertices;
457 if (lane.IsStraight()) {
458 // Mesh optimization: If the lane is straight just add vertices at the
459 // begining and at the end of it
460 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
461 l_vertices.push_back(edges.second);
462 l_vertices.push_back(edges.second + height_vector);
463 } else {
464 // Iterate over the lane's 's' and store the vertices based on it's width
465 do {
466 // Get the location of the edges of the current lane at the current waypoint
467 const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
468 l_vertices.push_back(edges.second);
469 l_vertices.push_back(edges.second + height_vector);
470
471 // Update the current waypoint's "s"
472 s_current += road_param.resolution;
473 } while(s_current < s_end);
474 }
475
476 // This ensures the mesh is constant and have no gaps between roads,
477 // adding geometry at the very end of the lane
478 if (s_end - (s_current - road_param.resolution) > EPSILON) {
479 const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
480 l_vertices.push_back(edges.second);
481 l_vertices.push_back(edges.second + height_vector);
482 }
483
484 // Add the adient material, create the strip and close the material
485 out_mesh.AddMaterial(
486 lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
487 out_mesh.AddTriangleStrip(l_vertices);
488 out_mesh.EndMaterial();
489 return std::make_unique<Mesh>(out_mesh);
490 }
491
492 std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
493 const road::Road &road) const {
494 std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
495 for (auto &&lane_section : road.GetLaneSections()) {
496 auto section_uptr_list = GenerateWithMaxLen(lane_section);
497 mesh_uptr_list.insert(
498 mesh_uptr_list.end(),
499 std::make_move_iterator(section_uptr_list.begin()),
500 std::make_move_iterator(section_uptr_list.end()));
501 }
502 return mesh_uptr_list;
503 }
504
505 std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
506 const road::LaneSection &lane_section) const {
507 std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
508 if (lane_section.GetLength() < road_param.max_road_len) {
509 mesh_uptr_list.emplace_back(Generate(lane_section));
510 } else {
511 double s_current = lane_section.GetDistance() + EPSILON;
512 const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
513 while(s_current + road_param.max_road_len < s_end) {
514 const auto s_until = s_current + road_param.max_road_len;
515 Mesh lane_section_mesh;
516 for (auto &&lane_pair : lane_section.GetLanes()) {
517 lane_section_mesh += *Generate(lane_pair.second, s_current, s_until);
518 }
519 mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
520 s_current = s_until;
521 }
522 if (s_end - s_current > EPSILON) {
523 Mesh lane_section_mesh;
524 for (auto &&lane_pair : lane_section.GetLanes()) {
525 lane_section_mesh += *Generate(lane_pair.second, s_current, s_end);
526 }
527 mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
528 }
529 }
530 return mesh_uptr_list;
531 }
532
533std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
534 const road::Road &road) const {
535 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
536 for (auto &&lane_section : road.GetLaneSections()) {
537 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> section_uptr_list = GenerateOrderedWithMaxLen(lane_section);
538 mesh_uptr_list.insert(
539 std::make_move_iterator(section_uptr_list.begin()),
540 std::make_move_iterator(section_uptr_list.end()));
541 }
542 return mesh_uptr_list;
543 }
544
545 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
546 const road::LaneSection &lane_section) const {
547 const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
548 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
549
550 if (lane_section.GetLength() < road_param.max_road_len) {
551 GenerateLaneSectionOrdered(lane_section, mesh_uptr_list);
552 } else {
553 double s_current = lane_section.GetDistance() + EPSILON;
554 const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
555 std::vector<size_t> redirections;
556 while(s_current + road_param.max_road_len < s_end) {
557 const auto s_until = s_current + road_param.max_road_len;
558
559 for (auto &&lane_pair : lane_section.GetLanes()) {
560 Mesh lane_section_mesh;
561 switch(lane_pair.second.GetType())
562 {
566 {
567 lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until);
568 break;
569 }
573 {
574 lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until);
575 break;
576 }
577 default:
578 {
579 lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until);
580 break;
581 }
582 }
583 auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
584 if (it == redirections.end()) {
585 redirections.push_back(lane_pair.first);
586 it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
587 }
588
589 size_t PosToAdd = it - redirections.begin();
590 if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
591 mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
592 } else {
593 uint32_t verticesinwidth = SelectVerticesInWidth(vertices_in_width, lane_pair.second.GetType());
594 (mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth);
595 }
596 }
597 s_current = s_until;
598 }
599 if (s_end - s_current > EPSILON) {
600 for (auto &&lane_pair : lane_section.GetLanes()) {
601 Mesh lane_section_mesh;
602 switch(lane_pair.second.GetType())
603 {
607 {
608 lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end);
609 break;
610 }
614 {
615 lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end);
616 break;
617 }
618 default:
619 {
620 lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end);
621 break;
622 }
623 }
624
625 auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
626 if (it == redirections.end()) {
627 redirections.push_back(lane_pair.first);
628 it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
629 }
630
631 size_t PosToAdd = it - redirections.begin();
632
633 if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
634 mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
635 } else {
636 *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh;
637 }
638 }
639 }
640 }
641 return mesh_uptr_list;
642 }
643
644 std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
645 const road::Road &road) const {
646 std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
647 for (auto &&lane_section : road.GetLaneSections()) {
648 auto section_uptr_list = GenerateWallsWithMaxLen(lane_section);
649 mesh_uptr_list.insert(
650 mesh_uptr_list.end(),
651 std::make_move_iterator(section_uptr_list.begin()),
652 std::make_move_iterator(section_uptr_list.end()));
653 }
654 return mesh_uptr_list;
655 }
656
657 std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
658 const road::LaneSection &lane_section) const {
659 std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
660
661 const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
662 1 : lane_section.GetLanes().begin()->first;
663 const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
664 -1 : lane_section.GetLanes().rbegin()->first;
665
666 if (lane_section.GetLength() < road_param.max_road_len) {
667 mesh_uptr_list.emplace_back(GenerateWalls(lane_section));
668 } else {
669 double s_current = lane_section.GetDistance() + EPSILON;
670 const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
671 while(s_current + road_param.max_road_len < s_end) {
672 const auto s_until = s_current + road_param.max_road_len;
673 Mesh lane_section_mesh;
674 for (auto &&lane_pair : lane_section.GetLanes()) {
675 const auto &lane = lane_pair.second;
676 if (lane.GetId() == max_lane) {
677 lane_section_mesh += *GenerateLeftWall(lane, s_current, s_until);
678 }
679 if (lane.GetId() == min_lane) {
680 lane_section_mesh += *GenerateRightWall(lane, s_current, s_until);
681 }
682 }
683 mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
684 s_current = s_until;
685 }
686 if (s_end - s_current > EPSILON) {
687 Mesh lane_section_mesh;
688 for (auto &&lane_pair : lane_section.GetLanes()) {
689 const auto &lane = lane_pair.second;
690 if (lane.GetId() == max_lane) {
691 lane_section_mesh += *GenerateLeftWall(lane, s_current, s_end);
692 }
693 if (lane.GetId() == min_lane) {
694 lane_section_mesh += *GenerateRightWall(lane, s_current, s_end);
695 }
696 }
697 mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
698 }
699 }
700 return mesh_uptr_list;
701 }
702
703 std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateAllWithMaxLen(
704 const road::Road &road) const {
705 std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
706
707 // Get road meshes
708 auto roads = GenerateWithMaxLen(road);
709 mesh_uptr_list.insert(
710 mesh_uptr_list.end(),
711 std::make_move_iterator(roads.begin()),
712 std::make_move_iterator(roads.end()));
713
714 // Get wall meshes only if is not a junction
715 if (!road.IsJunction()) {
716 auto walls = GenerateWallsWithMaxLen(road);
717
718 if (roads.size() == walls.size()) {
719 for (size_t i = 0; i < walls.size(); ++i) {
720 *mesh_uptr_list[i] += *walls[i];
721 }
722 } else {
723 mesh_uptr_list.insert(
724 mesh_uptr_list.end(),
725 std::make_move_iterator(walls.begin()),
726 std::make_move_iterator(walls.end()));
727 }
728 }
729
730 return mesh_uptr_list;
731 }
732
734 const road::Road &road,
735 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& roads
736 ) const {
737
738 // Get road meshes
739 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> result = GenerateOrderedWithMaxLen(road);
740 for (auto &pair_map : result)
741 {
742 std::vector<std::unique_ptr<Mesh>>& origin = roads[pair_map.first];
743 std::vector<std::unique_ptr<Mesh>>& source = pair_map.second;
744 std::move(source.begin(), source.end(), std::back_inserter(origin));
745 }
746 }
747
749 const road::Road& road,
750 std::vector<std::unique_ptr<Mesh>>& inout,
751 std::vector<std::string>& outinfo ) const
752 {
753 for (auto&& lane_section : road.GetLaneSections()) {
754 for (auto&& lane : lane_section.GetLanes()) {
755 if (lane.first != 0) {
756 switch(lane.second.GetType())
757 {
761 {
762 GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo);
763 outinfo.push_back("white");
764 break;
765 }
766 }
767 } else {
768 if(lane.second.GetType() == road::Lane::LaneType::None ){
769 GenerateLaneMarksForCenterLine(road, lane_section, lane.second, inout, outinfo);
770 outinfo.push_back("yellow");
771 }
772 }
773 }
774 }
775 }
776
778 const road::LaneSection& lane_section,
779 const road::Lane& lane,
780 std::vector<std::unique_ptr<Mesh>>& inout,
781 std::vector<std::string>& outinfo ) const {
782 Mesh out_mesh;
783 const double s_start = lane_section.GetDistance();
784 const double s_end = lane_section.GetDistance() + lane_section.GetLength();
785 double s_current = s_start;
786 std::vector<geom::Vector3D> vertices;
787 std::vector<size_t> indices;
788
789 do {
790 //Get Lane info
792 if (road_info_mark != nullptr) {
793 carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
794
795 switch (lane_mark_info.type) {
797 size_t currentIndex = out_mesh.GetVertices().size() + 1;
798
799 std::pair<geom::Vector3D, geom::Vector3D> edges =
800 ComputeEdgesForLanemark(lane_section, lane, s_current, lane_mark_info.width);
801
802 out_mesh.AddVertex(edges.first);
803 out_mesh.AddVertex(edges.second);
804
805 out_mesh.AddIndex(currentIndex);
806 out_mesh.AddIndex(currentIndex + 1);
807 out_mesh.AddIndex(currentIndex + 2);
808
809 out_mesh.AddIndex(currentIndex + 1);
810 out_mesh.AddIndex(currentIndex + 3);
811 out_mesh.AddIndex(currentIndex + 2);
812
813 s_current += road_param.resolution;
814 break;
815 }
817 size_t currentIndex = out_mesh.GetVertices().size() + 1;
818
819 std::pair<geom::Vector3D, geom::Vector3D> edges =
820 ComputeEdgesForLanemark(lane_section, lane, s_current, lane_mark_info.width);
821
822 out_mesh.AddVertex(edges.first);
823 out_mesh.AddVertex(edges.second);
824
825 s_current += road_param.resolution * 3;
826 if (s_current > s_end)
827 {
828 s_current = s_end;
829 }
830
831 edges = ComputeEdgesForLanemark(lane_section, lane, s_current, lane_mark_info.width);
832
833 out_mesh.AddVertex(edges.first);
834 out_mesh.AddVertex(edges.second);
835
836 out_mesh.AddIndex(currentIndex);
837 out_mesh.AddIndex(currentIndex + 1);
838 out_mesh.AddIndex(currentIndex + 2);
839
840 out_mesh.AddIndex(currentIndex + 1);
841 out_mesh.AddIndex(currentIndex + 3);
842 out_mesh.AddIndex(currentIndex + 2);
843
844 s_current += road_param.resolution * 3;
845
846 break;
847 }
849 s_current += road_param.resolution;
850 break;
851 }
853 s_current += road_param.resolution;
854 break;
855 }
857 s_current += road_param.resolution;
858 break;
859 }
861 s_current += road_param.resolution;
862 break;
863 }
865 s_current += road_param.resolution;
866 break;
867 }
869 s_current += road_param.resolution;
870 break;
871 }
873 s_current += road_param.resolution;
874 break;
875 }
877 s_current += road_param.resolution;
878 break;
879 }
880 default: {
881 s_current += road_param.resolution;
882 break;
883 }
884 }
885 }
886 } while (s_current < s_end);
887
888 if (out_mesh.IsValid()) {
890 if (road_info_mark != nullptr) {
891 carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
892
893 std::pair<geom::Vector3D, geom::Vector3D> edges =
894 ComputeEdgesForLanemark(lane_section, lane, s_end, lane_mark_info.width);
895
896 out_mesh.AddVertex(edges.first);
897 out_mesh.AddVertex(edges.second);
898 }
899 inout.push_back(std::make_unique<Mesh>(out_mesh));
900 }
901 }
902
904 const road::Road& road,
905 const road::LaneSection& lane_section,
906 const road::Lane& lane,
907 std::vector<std::unique_ptr<Mesh>>& inout,
908 std::vector<std::string>& outinfo ) const
909 {
910 Mesh out_mesh;
911 const double s_start = lane_section.GetDistance();
912 const double s_end = lane_section.GetDistance() + lane_section.GetLength();
913 double s_current = s_start;
914 std::vector<geom::Vector3D> vertices;
915 std::vector<size_t> indices;
916
917 do {
918 //Get Lane info
920 if (road_info_mark != nullptr) {
921 carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
922
923 switch (lane_mark_info.type) {
925 size_t currentIndex = out_mesh.GetVertices().size() + 1;
926
927 carla::road::element::DirectedPoint rightpoint = road.GetDirectedPointIn(s_current);
928 carla::road::element::DirectedPoint leftpoint = rightpoint;
929
930 rightpoint.ApplyLateralOffset(lane_mark_info.width * 0.5);
931 leftpoint.ApplyLateralOffset(lane_mark_info.width * -0.5);
932
933 // Unreal's Y axis hack
934 rightpoint.location.y *= -1;
935 leftpoint.location.y *= -1;
936
937 out_mesh.AddVertex(rightpoint.location);
938 out_mesh.AddVertex(leftpoint.location);
939
940 out_mesh.AddIndex(currentIndex);
941 out_mesh.AddIndex(currentIndex + 1);
942 out_mesh.AddIndex(currentIndex + 2);
943
944 out_mesh.AddIndex(currentIndex + 1);
945 out_mesh.AddIndex(currentIndex + 3);
946 out_mesh.AddIndex(currentIndex + 2);
947
948 s_current += road_param.resolution;
949 break;
950 }
952 size_t currentIndex = out_mesh.GetVertices().size() + 1;
953
954 std::pair<geom::Vector3D, geom::Vector3D> edges =
955 ComputeEdgesForLanemark(lane_section, lane, s_current, lane_mark_info.width);
956
957 out_mesh.AddVertex(edges.first);
958 out_mesh.AddVertex(edges.second);
959
960 s_current += road_param.resolution * 3;
961 if (s_current > s_end) {
962 s_current = s_end;
963 }
964
965 edges = ComputeEdgesForLanemark(lane_section, lane, s_current, lane_mark_info.width);
966
967 out_mesh.AddVertex(edges.first);
968 out_mesh.AddVertex(edges.second);
969
970 out_mesh.AddIndex(currentIndex);
971 out_mesh.AddIndex(currentIndex + 1);
972 out_mesh.AddIndex(currentIndex + 2);
973
974 out_mesh.AddIndex(currentIndex + 1);
975 out_mesh.AddIndex(currentIndex + 3);
976 out_mesh.AddIndex(currentIndex + 2);
977
978 s_current += road_param.resolution * 3;
979
980 break;
981 }
983 s_current += road_param.resolution;
984 break;
985 }
987 s_current += road_param.resolution;
988 break;
989 }
991 s_current += road_param.resolution;
992 break;
993 }
995 s_current += road_param.resolution;
996 break;
997 }
999 s_current += road_param.resolution;
1000 break;
1001 }
1003 s_current += road_param.resolution;
1004 break;
1005 }
1007 s_current += road_param.resolution;
1008 break;
1009 }
1011 s_current += road_param.resolution;
1012 break;
1013 }
1014 default: {
1015 s_current += road_param.resolution;
1016 break;
1017 }
1018 }
1019 }
1020 } while (s_current < s_end);
1021
1022 if (out_mesh.IsValid()) {
1024 if (road_info_mark != nullptr)
1025 {
1026 carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
1027 carla::road::element::DirectedPoint rightpoint = road.GetDirectedPointIn(s_current);
1028 carla::road::element::DirectedPoint leftpoint = rightpoint;
1029
1030 rightpoint.ApplyLateralOffset(lane_mark_info.width * 0.5f);
1031 leftpoint.ApplyLateralOffset(lane_mark_info.width * -0.5f);
1032
1033 // Unreal's Y axis hack
1034 rightpoint.location.y *= -1;
1035 leftpoint.location.y *= -1;
1036
1037 out_mesh.AddVertex(rightpoint.location);
1038 out_mesh.AddVertex(leftpoint.location);
1039
1040 }
1041 inout.push_back(std::make_unique<Mesh>(out_mesh));
1042 }
1043 }
1044
1051 std::vector<VertexWeight> neighbors;
1052 };
1058
1059 // Helper function to compute the weight of neighboring vertices
1061 const MeshFactory::RoadParameters &road_param,
1062 const VertexInfo &vertex_info,
1063 const VertexInfo &neighbor_info) {
1064 const float distance3D = geom::Math::Distance(*vertex_info.vertex, *neighbor_info.vertex);
1065 // Ignore vertices beyond a certain distance
1066 if(distance3D > road_param.max_weight_distance) {
1067 return {neighbor_info.vertex, 0};
1068 }
1069 if(abs(distance3D) < EPSILON) {
1070 return {neighbor_info.vertex, 0};
1071 }
1072 float weight = geom::Math::Clamp<float>(1.0f / distance3D, 0.0f, 100000.0f);
1073
1074 // Additional weight to vertices in the same lane
1075 if(vertex_info.lane_mesh_idx == neighbor_info.lane_mesh_idx) {
1076 weight *= road_param.same_lane_weight_multiplier;
1077 // Further additional weight for fixed verices
1078 if(neighbor_info.is_static) {
1079 weight *= road_param.lane_ends_multiplier;
1080 }
1081 }
1082 return {neighbor_info.vertex, weight};
1083 }
1084
1085 // Helper function to compute neighborhoord of vertices and their weights
1086 std::vector<VertexNeighbors> GetVertexNeighborhoodAndWeights(
1087 const MeshFactory::RoadParameters &road_param,
1088 std::vector<std::unique_ptr<Mesh>> &lane_meshes) {
1089 // Build rtree for neighborhood queries
1091 using Point = Rtree::BPoint;
1092 Rtree rtree;
1093 for (size_t lane_mesh_idx = 0; lane_mesh_idx < lane_meshes.size(); ++lane_mesh_idx) {
1094 auto& mesh = lane_meshes[lane_mesh_idx];
1095 for(size_t i = 0; i < mesh->GetVerticesNum(); ++i) {
1096 auto& vertex = mesh->GetVertices()[i];
1097 Point point(vertex.x, vertex.y, vertex.z);
1098 if (i < 2 || i >= mesh->GetVerticesNum() - 2) {
1099 rtree.InsertElement({point, {&vertex, lane_mesh_idx, true}});
1100 } else {
1101 rtree.InsertElement({point, {&vertex, lane_mesh_idx, false}});
1102 }
1103 }
1104 }
1105
1106 // Find neighbors for each vertex and compute their weight
1107 std::vector<VertexNeighbors> vertices_neighborhoods;
1108 for (size_t lane_mesh_idx = 0; lane_mesh_idx < lane_meshes.size(); ++lane_mesh_idx) {
1109 auto& mesh = lane_meshes[lane_mesh_idx];
1110 for(size_t i = 0; i < mesh->GetVerticesNum(); ++i) {
1111 if (i > 2 && i < mesh->GetVerticesNum() - 2) {
1112 auto& vertex = mesh->GetVertices()[i];
1113 Point point(vertex.x, vertex.y, vertex.z);
1114 auto closest_vertices = rtree.GetNearestNeighbours(point, 20);
1115 VertexNeighbors vertex_neighborhood;
1116 vertex_neighborhood.vertex = &vertex;
1117 for(auto& close_vertex : closest_vertices) {
1118 auto &vertex_info = close_vertex.second;
1119 if(&vertex == vertex_info.vertex) {
1120 continue;
1121 }
1122 auto vertex_weight = ComputeVertexWeight(
1123 road_param, {&vertex, lane_mesh_idx, false}, vertex_info);
1124 if(vertex_weight.weight > 0)
1125 vertex_neighborhood.neighbors.push_back(vertex_weight);
1126 }
1127 vertices_neighborhoods.push_back(vertex_neighborhood);
1128 }
1129 }
1130 }
1131 return vertices_neighborhoods;
1132 }
1133
1134 std::unique_ptr<Mesh> MeshFactory::MergeAndSmooth(std::vector<std::unique_ptr<Mesh>> &lane_meshes) const {
1135 geom::Mesh out_mesh;
1136
1137 auto vertices_neighborhoods = GetVertexNeighborhoodAndWeights(road_param, lane_meshes);
1138
1139 // Laplacian function
1140 auto Laplacian = [&](const Mesh::vertex_type* vertex, const std::vector<VertexWeight> &neighbors) -> double {
1141 double sum = 0;
1142 double sum_weight = 0;
1143 for(auto &element : neighbors) {
1144 sum += (element.vertex->z - vertex->z)*element.weight;
1145 sum_weight += element.weight;
1146 }
1147 if(sum_weight > 0)
1148 return sum / sum_weight;
1149 else
1150 return 0;
1151 };
1152 // Run iterative algorithm
1153 double lambda = 0.5;
1154 int iterations = 100;
1155 for(int iter = 0; iter < iterations; ++iter) {
1156 for (auto& vertex_neighborhood : vertices_neighborhoods) {
1157 auto * vertex = vertex_neighborhood.vertex;
1158 vertex->z += static_cast<float>(lambda*Laplacian(vertex, vertex_neighborhood.neighbors));
1159 }
1160 }
1161
1162 for(auto &mesh : lane_meshes) {
1163 out_mesh += *mesh;
1164 }
1165
1166 return std::make_unique<Mesh>(out_mesh);
1167 }
1168
1169 uint32_t MeshFactory::SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type)
1170 {
1171 switch(type)
1172 {
1176 {
1177 return default_num_vertices;
1178 }
1182 {
1183 return 6;
1184 }
1185 default:
1186 {
1187 return 2;
1188 }
1189 }
1190 }
1191
1192 std::pair<geom::Vector3D, geom::Vector3D> MeshFactory::ComputeEdgesForLanemark(
1193 const road::LaneSection& lane_section,
1194 const road::Lane& lane,
1195 const double s_current,
1196 const double lanemark_width) const {
1197 std::pair<geom::Vector3D, geom::Vector3D> edges =
1199
1200 geom::Vector3D director;
1201 if (edges.first != edges.second) {
1202 director = edges.second - edges.first;
1203 director /= director.Length();
1204 } else {
1205 const std::map<road::LaneId, road::Lane> & lanes = lane_section.GetLanes();
1206 for (const auto& lane_pair : lanes) {
1207 std::pair<geom::Vector3D, geom::Vector3D> another_edge =
1208 lane_pair.second.GetCornerPositions(s_current, road_param.extra_lane_width);
1209 if (another_edge.first != another_edge.second) {
1210 director = another_edge.second - another_edge.first;
1211 director /= director.Length();
1212 break;
1213 }
1214 }
1215 }
1216 geom::Vector3D endmarking = edges.first + director * lanemark_width;
1217 return std::make_pair(edges.first, endmarking);
1218 }
1219
1220} // namespace geom
1221} // namespace carla
#define DEBUG_ASSERT(predicate)
Definition Debug.h:66
#define RELEASE_ASSERT(pred)
Definition Debug.h:84
static auto Distance(const Vector3D &a, const Vector3D &b)
Definition Math.h:78
static uint32_t SelectVerticesInWidth(uint32_t default_num_vertices, road::Lane::LaneType type)
std::unique_ptr< Mesh > GenerateRightWall(const road::Lane &lane, const double s_start, const double s_end) const
Generates a wall-like mesh at the right side of the lane
std::unique_ptr< Mesh > GenerateSidewalk(const road::LaneSection &lane_section) const
std::unique_ptr< Mesh > GenerateLeftWall(const road::Lane &lane, const double s_start, const double s_end) const
Generates a wall-like mesh at the left side of the lane
std::unique_ptr< Mesh > MergeAndSmooth(std::vector< std::unique_ptr< Mesh > > &lane_meshes) const
std::pair< geom::Vector3D, geom::Vector3D > ComputeEdgesForLanemark(const road::LaneSection &lane_section, const road::Lane &lane, const double s_current, const double lanemark_width) const
void GenerateLaneMarksForCenterLine(const road::Road &road, const road::LaneSection &lane_section, const road::Lane &lane, std::vector< std::unique_ptr< Mesh > > &inout, std::vector< std::string > &outinfo) const
std::vector< std::unique_ptr< Mesh > > GenerateWallsWithMaxLen(const road::Road &road) const
Generates a list of meshes that defines a road safety wall with a maximum length
void GenerateLaneMarkForRoad(const road::Road &road, std::vector< std::unique_ptr< Mesh > > &inout, std::vector< std::string > &outinfo) const
MeshFactory(rpc::OpendriveGenerationParameters params=rpc::OpendriveGenerationParameters())
RoadParameters road_param
std::unique_ptr< Mesh > Generate(const road::Road &road) const
Generates a mesh that defines a road
void GenerateLaneMarksForNotCenterLine(const road::LaneSection &lane_section, const road::Lane &lane, std::vector< std::unique_ptr< Mesh > > &inout, std::vector< std::string > &outinfo) const
void GenerateLaneSectionOrdered(const road::LaneSection &lane_section, std::map< carla::road::Lane::LaneType, std::vector< std::unique_ptr< Mesh > > > &result) const
Generates a mesh that defines a lane section
std::unique_ptr< Mesh > GenerateTesselated(const road::Lane &lane, const double s_start, const double s_end) const
Generates a mesh that defines a lane from a given s start and end with bigger tesselation
std::vector< std::unique_ptr< Mesh > > GenerateAllWithMaxLen(const road::Road &road) const
Generates a chunked road with all the features needed for simulation
std::vector< std::unique_ptr< Mesh > > GenerateWithMaxLen(const road::Road &road) const
Generates a list of meshes that defines a road with a maximum length
std::map< carla::road::Lane::LaneType, std::vector< std::unique_ptr< Mesh > > > GenerateOrderedWithMaxLen(const road::Road &road) const
Generates a list of meshes that defines a road with a maximum length
std::unique_ptr< Mesh > GenerateWalls(const road::LaneSection &lane_section) const
Genrates a mesh representing a wall on the road corners to avoid cars falling down
void GenerateAllOrderedWithMaxLen(const road::Road &road, std::map< road::Lane::LaneType, std::vector< std::unique_ptr< Mesh > > > &roads) const
Mesh data container, validator and exporter.
Definition Mesh.h:44
void AddIndex(index_type index)
Appends a index to the indexes list.
Definition Mesh.cpp:101
void AddVertex(vertex_type vertex)
Appends a vertex to the vertices list.
Definition Mesh.cpp:89
void AddVertices(const std::vector< vertex_type > &vertices)
Appends a vertex to the vertices list.
Definition Mesh.cpp:93
bool IsValid() const
Check if the mesh can be valid or not.
Definition Mesh.cpp:20
void AddUVs(const std::vector< uv_type > &uv)
Appends uvs.
Definition Mesh.cpp:109
void AddMaterial(const std::string &material_name)
Starts applying a new material to the new added triangles.
Definition Mesh.cpp:113
void EndMaterial()
Stops applying the material to the new added triangles.
Definition Mesh.cpp:129
void AddTriangleStrip(const std::vector< vertex_type > &vertices)
Adds a triangle strip to the mesh, vertex order is counterclockwise.
Definition Mesh.cpp:47
const std::vector< vertex_type > & GetVertices() const
Definition Mesh.cpp:255
Rtree class working with 3D point clouds.
Definition Rtree.h:30
double GetDistance() const
std::map< LaneId, Lane > & GetLanes()
bool IsStraight() const
Checks whether the geometry is straight or not
Definition Lane.cpp:67
LaneType GetType() const
Definition Lane.cpp:38
const T * GetInfo(const double s) const
Definition Lane.h:79
LaneType
Can be used as flags
Definition Lane.h:29
double GetDistance() const
Definition Lane.cpp:46
std::pair< geom::Vector3D, geom::Vector3D > GetCornerPositions(const double s, const float extra_width=0.f) const
Computes the location of the edges given a s
Definition Lane.cpp:206
LaneId GetId() const
Definition Lane.cpp:34
double GetLength() const
Definition Lane.cpp:51
auto GetLaneSections() const
Definition Road.h:127
element::DirectedPoint GetDirectedPointIn(const double s) const
Returns a directed point on the center of the road (lane 0), with the corresponding laneOffset and el...
Definition Road.cpp:180
bool IsJunction() const
Definition Road.cpp:42
Each lane within a road cross section can be provided with several road markentries.
static constexpr double EPSILON
We use this epsilon to shift the waypoints away from the edges of the lane sections to avoid floating...
static VertexWeight ComputeVertexWeight(const MeshFactory::RoadParameters &road_param, const VertexInfo &vertex_info, const VertexInfo &neighbor_info)
static constexpr double MESH_EPSILON
std::vector< VertexNeighbors > GetVertexNeighborhoodAndWeights(const MeshFactory::RoadParameters &road_param, std::vector< std::unique_ptr< Mesh > > &lane_meshes)
This file contains definitions of common data structures used in traffic manager.
Definition Carla.cpp:133
Parameters for the road generation
Mesh::vertex_type * vertex
std::vector< VertexWeight > neighbors
Mesh::vertex_type * vertex
void ApplyLateralOffset(float lateral_offset)
Definition Geometry.cpp:28
Seting for map generation from opendrive without additional geometry