CARLA
MeshFactory.cpp
Go to the documentation of this file.
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>
16 #include <carla/road/Deformation.h>
17 
18 namespace carla {
19 namespace 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);
26  road_param.vertex_width_resolution = static_cast<float>(params.vertex_width_resolution);
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 =
157  lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
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  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
210  out_mesh += *GenerateTesselated(lane_pair.second);
211  }else{
212  out_mesh += *GenerateSidewalk(lane_pair.second);
213  }
214 
215  if( result[lane_pair.second.GetType()].size() <= PosToAdd ){
216  result[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(out_mesh));
217  } else {
218  uint32_t verticesinwidth = 0;
219  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
220  verticesinwidth = vertices_in_width;
221  }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
222  verticesinwidth = 6;
223  }else{
224  verticesinwidth = 2;
225  }
226  (result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, verticesinwidth);
227  }
228  }
229  }
230 
231 
232  std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::LaneSection &lane_section) const{
233  Mesh out_mesh;
234  for (auto &&lane_pair : lane_section.GetLanes()) {
235  const double s_start = lane_pair.second.GetDistance() + EPSILON;
236  const double s_end = lane_pair.second.GetDistance() + lane_pair.second.GetLength() - EPSILON;
237  out_mesh += *GenerateSidewalk(lane_pair.second, s_start, s_end);
238  }
239  return std::make_unique<Mesh>(out_mesh);
240  }
241  std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::Lane &lane) const{
242  const double s_start = lane.GetDistance() + EPSILON;
243  const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
244  return GenerateSidewalk(lane, s_start, s_end);
245  }
246  std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(
247  const road::Lane &lane, const double s_start,
248  const double s_end ) const {
249 
251  DEBUG_ASSERT(s_start >= 0.0);
252  DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
253  DEBUG_ASSERT(s_end >= EPSILON);
254  DEBUG_ASSERT(s_start < s_end);
255  // The lane with lane_id 0 have no physical representation in OpenDRIVE
256  Mesh out_mesh;
257  if (lane.GetId() == 0) {
258  return std::make_unique<Mesh>(out_mesh);
259  }
260  double s_current = s_start;
261 
262  std::vector<geom::Vector3D> vertices;
263  // Ensure minimum vertices in width are two
264  const int vertices_in_width = 6;
265  const int segments_number = vertices_in_width - 1;
266  std::vector<geom::Vector2D> uvs;
267  int uvy = 0;
268 
269  // Iterate over the lane's 's' and store the vertices based on it's width
270  do {
271  // Get the location of the edges of the current lane at the current waypoint
272  std::pair<geom::Vector3D, geom::Vector3D> edges =
274 
275  geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
276  geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
277  vertices.push_back(low_vertex_first);
278  uvs.push_back(geom::Vector2D(0, uvy));
279 
280  vertices.push_back(edges.first);
281  uvs.push_back(geom::Vector2D(1, uvy));
282 
283  vertices.push_back(edges.first);
284  uvs.push_back(geom::Vector2D(1, uvy));
285 
286  vertices.push_back(edges.second);
287  uvs.push_back(geom::Vector2D(2, uvy));
288 
289  vertices.push_back(edges.second);
290  uvs.push_back(geom::Vector2D(2, uvy));
291 
292  vertices.push_back(low_vertex_second);
293  uvs.push_back(geom::Vector2D(3, uvy));
294 
295  // Update the current waypoint's "s"
296  s_current += road_param.resolution;
297  uvy++;
298  } while (s_current < s_end);
299 
300  // This ensures the mesh is constant and have no gaps between roads,
301  // adding geometry at the very end of the lane
302 
303  if (s_end - (s_current - road_param.resolution) > EPSILON) {
304  std::pair<carla::geom::Vector3D, carla::geom::Vector3D> edges =
305  lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
306 
307  geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
308  geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
309 
310  vertices.push_back(low_vertex_first);
311  uvs.push_back(geom::Vector2D(0, uvy));
312 
313  vertices.push_back(edges.first);
314  uvs.push_back(geom::Vector2D(1, uvy));
315 
316  vertices.push_back(edges.first);
317  uvs.push_back(geom::Vector2D(1, uvy));
318 
319  vertices.push_back(edges.second);
320  uvs.push_back(geom::Vector2D(2, uvy));
321 
322  vertices.push_back(edges.second);
323  uvs.push_back(geom::Vector2D(2, uvy));
324 
325  vertices.push_back(low_vertex_second);
326  uvs.push_back(geom::Vector2D(3, uvy));
327 
328  }
329 
330  out_mesh.AddVertices(vertices);
331  out_mesh.AddUVs(uvs);
332  // Add the adient material, create the strip and close the material
333  out_mesh.AddMaterial(
334  lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
335 
336  const int number_of_rows = (vertices.size() / vertices_in_width);
337 
338  for (size_t i = 0; i < (number_of_rows - 1); ++i) {
339  for (size_t j = 0; j < vertices_in_width - 1; ++j) {
340 
341  if(j == 1 || j == 3){
342  continue;
343  }
344 
345  out_mesh.AddIndex( j + ( i * vertices_in_width ) + 1);
346  out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
347  out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
348 
349  out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
350  out_mesh.AddIndex( ( j + 1 ) + ( ( i + 1 ) * vertices_in_width ) + 1);
351  out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
352 
353  }
354  }
355  out_mesh.EndMaterial();
356  return std::make_unique<Mesh>(out_mesh);
357  }
358  std::unique_ptr<Mesh> MeshFactory::GenerateWalls(const road::LaneSection &lane_section) const {
359  Mesh out_mesh;
360 
361  const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
362  1 : lane_section.GetLanes().begin()->first;
363  const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
364  -1 : lane_section.GetLanes().rbegin()->first;
365 
366  for (auto &&lane_pair : lane_section.GetLanes()) {
367  const auto &lane = lane_pair.second;
368  const double s_start = lane.GetDistance() + EPSILON;
369  const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
370  if (lane.GetId() == max_lane) {
371  out_mesh += *GenerateLeftWall(lane, s_start, s_end);
372  }
373  if (lane.GetId() == min_lane) {
374  out_mesh += *GenerateRightWall(lane, s_start, s_end);
375  }
376  }
377  return std::make_unique<Mesh>(out_mesh);
378  }
379 
380  std::unique_ptr<Mesh> MeshFactory::GenerateRightWall(
381  const road::Lane &lane, const double s_start, const double s_end) const {
383  DEBUG_ASSERT(s_start >= 0.0);
384  DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
385  DEBUG_ASSERT(s_end >= EPSILON);
386  DEBUG_ASSERT(s_start < s_end);
387  // The lane with lane_id 0 have no physical representation in OpenDRIVE
388  Mesh out_mesh;
389  if (lane.GetId() == 0) {
390  return std::make_unique<Mesh>(out_mesh);
391  }
392  double s_current = s_start;
393  const geom::Vector3D height_vector = geom::Vector3D(0.f, 0.f, road_param.wall_height);
394 
395  std::vector<geom::Vector3D> r_vertices;
396  if (lane.IsStraight()) {
397  // Mesh optimization: If the lane is straight just add vertices at the
398  // begining and at the end of it
399  const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
400  r_vertices.push_back(edges.first + height_vector);
401  r_vertices.push_back(edges.first);
402  } else {
403  // Iterate over the lane's 's' and store the vertices based on it's width
404  do {
405  // Get the location of the edges of the current lane at the current waypoint
406  const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
407  r_vertices.push_back(edges.first + height_vector);
408  r_vertices.push_back(edges.first);
409 
410  // Update the current waypoint's "s"
411  s_current += road_param.resolution;
412  } while(s_current < s_end);
413  }
414 
415  // This ensures the mesh is constant and have no gaps between roads,
416  // adding geometry at the very end of the lane
417  if (s_end - (s_current - road_param.resolution) > EPSILON) {
418  const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
419  r_vertices.push_back(edges.first + height_vector);
420  r_vertices.push_back(edges.first);
421  }
422 
423  // Add the adient material, create the strip and close the material
424  out_mesh.AddMaterial(
425  lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
426  out_mesh.AddTriangleStrip(r_vertices);
427  out_mesh.EndMaterial();
428  return std::make_unique<Mesh>(out_mesh);
429  }
430 
431  std::unique_ptr<Mesh> MeshFactory::GenerateLeftWall(
432  const road::Lane &lane, const double s_start, const double s_end) const {
434  DEBUG_ASSERT(s_start >= 0.0);
435  DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
436  DEBUG_ASSERT(s_end >= EPSILON);
437  DEBUG_ASSERT(s_start < s_end);
438  // The lane with lane_id 0 have no physical representation in OpenDRIVE
439  Mesh out_mesh;
440  if (lane.GetId() == 0) {
441  return std::make_unique<Mesh>(out_mesh);
442  }
443  double s_current = s_start;
444  const geom::Vector3D height_vector = geom::Vector3D(0.f, 0.f, road_param.wall_height);
445 
446  std::vector<geom::Vector3D> l_vertices;
447  if (lane.IsStraight()) {
448  // Mesh optimization: If the lane is straight just add vertices at the
449  // begining and at the end of it
450  const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
451  l_vertices.push_back(edges.second);
452  l_vertices.push_back(edges.second + height_vector);
453  } else {
454  // Iterate over the lane's 's' and store the vertices based on it's width
455  do {
456  // Get the location of the edges of the current lane at the current waypoint
457  const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
458  l_vertices.push_back(edges.second);
459  l_vertices.push_back(edges.second + height_vector);
460 
461  // Update the current waypoint's "s"
462  s_current += road_param.resolution;
463  } while(s_current < s_end);
464  }
465 
466  // This ensures the mesh is constant and have no gaps between roads,
467  // adding geometry at the very end of the lane
468  if (s_end - (s_current - road_param.resolution) > EPSILON) {
469  const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
470  l_vertices.push_back(edges.second);
471  l_vertices.push_back(edges.second + height_vector);
472  }
473 
474  // Add the adient material, create the strip and close the material
475  out_mesh.AddMaterial(
476  lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
477  out_mesh.AddTriangleStrip(l_vertices);
478  out_mesh.EndMaterial();
479  return std::make_unique<Mesh>(out_mesh);
480  }
481 
482  std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
483  const road::Road &road) const {
484  std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
485  for (auto &&lane_section : road.GetLaneSections()) {
486  auto section_uptr_list = GenerateWithMaxLen(lane_section);
487  mesh_uptr_list.insert(
488  mesh_uptr_list.end(),
489  std::make_move_iterator(section_uptr_list.begin()),
490  std::make_move_iterator(section_uptr_list.end()));
491  }
492  return mesh_uptr_list;
493  }
494 
495  std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
496  const road::LaneSection &lane_section) const {
497  std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
498  if (lane_section.GetLength() < road_param.max_road_len) {
499  mesh_uptr_list.emplace_back(Generate(lane_section));
500  } else {
501  double s_current = lane_section.GetDistance() + EPSILON;
502  const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
503  while(s_current + road_param.max_road_len < s_end) {
504  const auto s_until = s_current + road_param.max_road_len;
505  Mesh lane_section_mesh;
506  for (auto &&lane_pair : lane_section.GetLanes()) {
507  lane_section_mesh += *Generate(lane_pair.second, s_current, s_until);
508  }
509  mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
510  s_current = s_until;
511  }
512  if (s_end - s_current > EPSILON) {
513  Mesh lane_section_mesh;
514  for (auto &&lane_pair : lane_section.GetLanes()) {
515  lane_section_mesh += *Generate(lane_pair.second, s_current, s_end);
516  }
517  mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
518  }
519  }
520  return mesh_uptr_list;
521  }
522 
523 std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
524  const road::Road &road) const {
525  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
526  for (auto &&lane_section : road.GetLaneSections()) {
527  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> section_uptr_list = GenerateOrderedWithMaxLen(lane_section);
528  mesh_uptr_list.insert(
529  std::make_move_iterator(section_uptr_list.begin()),
530  std::make_move_iterator(section_uptr_list.end()));
531  }
532  return mesh_uptr_list;
533  }
534 
535  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
536  const road::LaneSection &lane_section) const {
537  const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
538  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
539 
540  if (lane_section.GetLength() < road_param.max_road_len) {
541  GenerateLaneSectionOrdered(lane_section, mesh_uptr_list);
542  } else {
543  double s_current = lane_section.GetDistance() + EPSILON;
544  const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
545  std::vector<size_t> redirections;
546  while(s_current + road_param.max_road_len < s_end) {
547  const auto s_until = s_current + road_param.max_road_len;
548 
549  for (auto &&lane_pair : lane_section.GetLanes()) {
550  Mesh lane_section_mesh;
551  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
552  lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until);
553  }else{
554  lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until);
555  }
556 
557  auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
558  if (it == redirections.end()) {
559  redirections.push_back(lane_pair.first);
560  it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
561  }
562 
563  size_t PosToAdd = it - redirections.begin();
564  if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
565  mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
566  } else {
567  uint32_t verticesinwidth = 0;
568  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
569  verticesinwidth = vertices_in_width;
570  }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
571  verticesinwidth = 6;
572  }else{
573  verticesinwidth = 2;
574  }
575  (mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth);
576  }
577  }
578  s_current = s_until;
579  }
580  if (s_end - s_current > EPSILON) {
581  for (auto &&lane_pair : lane_section.GetLanes()) {
582  Mesh lane_section_mesh;
583  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
584  lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end);
585  }else{
586  lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end);
587  }
588 
589  auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
590  if (it == redirections.end()) {
591  redirections.push_back(lane_pair.first);
592  it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
593  }
594 
595  size_t PosToAdd = it - redirections.begin();
596 
597  if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
598  mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
599  } else {
600  uint32_t verticesinwidth = 0;
601  if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
602  verticesinwidth = vertices_in_width;
603  }else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
604  verticesinwidth = 6;
605  }else{
606  verticesinwidth = 2;
607  }
608  *(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd]) += lane_section_mesh;
609  }
610  }
611  }
612  }
613  return mesh_uptr_list;
614  }
615 
616  std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
617  const road::Road &road) const {
618  std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
619  for (auto &&lane_section : road.GetLaneSections()) {
620  auto section_uptr_list = GenerateWallsWithMaxLen(lane_section);
621  mesh_uptr_list.insert(
622  mesh_uptr_list.end(),
623  std::make_move_iterator(section_uptr_list.begin()),
624  std::make_move_iterator(section_uptr_list.end()));
625  }
626  return mesh_uptr_list;
627  }
628 
629  std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
630  const road::LaneSection &lane_section) const {
631  std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
632 
633  const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
634  1 : lane_section.GetLanes().begin()->first;
635  const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
636  -1 : lane_section.GetLanes().rbegin()->first;
637 
638  if (lane_section.GetLength() < road_param.max_road_len) {
639  mesh_uptr_list.emplace_back(GenerateWalls(lane_section));
640  } else {
641  double s_current = lane_section.GetDistance() + EPSILON;
642  const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
643  while(s_current + road_param.max_road_len < s_end) {
644  const auto s_until = s_current + road_param.max_road_len;
645  Mesh lane_section_mesh;
646  for (auto &&lane_pair : lane_section.GetLanes()) {
647  const auto &lane = lane_pair.second;
648  if (lane.GetId() == max_lane) {
649  lane_section_mesh += *GenerateLeftWall(lane, s_current, s_until);
650  }
651  if (lane.GetId() == min_lane) {
652  lane_section_mesh += *GenerateRightWall(lane, s_current, s_until);
653  }
654  }
655  mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
656  s_current = s_until;
657  }
658  if (s_end - s_current > EPSILON) {
659  Mesh lane_section_mesh;
660  for (auto &&lane_pair : lane_section.GetLanes()) {
661  const auto &lane = lane_pair.second;
662  if (lane.GetId() == max_lane) {
663  lane_section_mesh += *GenerateLeftWall(lane, s_current, s_end);
664  }
665  if (lane.GetId() == min_lane) {
666  lane_section_mesh += *GenerateRightWall(lane, s_current, s_end);
667  }
668  }
669  mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
670  }
671  }
672  return mesh_uptr_list;
673  }
674 
675  std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateAllWithMaxLen(
676  const road::Road &road) const {
677  std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
678 
679  // Get road meshes
680  auto roads = GenerateWithMaxLen(road);
681  mesh_uptr_list.insert(
682  mesh_uptr_list.end(),
683  std::make_move_iterator(roads.begin()),
684  std::make_move_iterator(roads.end()));
685 
686  // Get wall meshes only if is not a junction
687  if (!road.IsJunction()) {
688  auto walls = GenerateWallsWithMaxLen(road);
689 
690  if (roads.size() == walls.size()) {
691  for (size_t i = 0; i < walls.size(); ++i) {
692  *mesh_uptr_list[i] += *walls[i];
693  }
694  } else {
695  mesh_uptr_list.insert(
696  mesh_uptr_list.end(),
697  std::make_move_iterator(walls.begin()),
698  std::make_move_iterator(walls.end()));
699  }
700  }
701 
702  return mesh_uptr_list;
703  }
704 
706  const road::Road &road,
707  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& roads
708  ) const {
709 
710  // Get road meshes
711  std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> result = GenerateOrderedWithMaxLen(road);
712  for (auto &pair_map : result)
713  {
714  std::vector<std::unique_ptr<Mesh>>& origin = roads[pair_map.first];
715  std::vector<std::unique_ptr<Mesh>>& source = pair_map.second;
716  std::move(source.begin(), source.end(), std::back_inserter(origin));
717  }
718  }
719 
721  const road::Road& road,
722  std::vector<std::unique_ptr<Mesh>>& inout,
723  std::vector<std::string>& outinfo ) const
724  {
725  for (auto&& lane_section : road.GetLaneSections()) {
726  for (auto&& lane : lane_section.GetLanes()) {
727  if (lane.first != 0) {
728  if(lane.second.GetType() == road::Lane::LaneType::Driving ){
729  GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout, outinfo);
730  outinfo.push_back("white");
731  }
732  } else {
733  if(lane.second.GetType() == road::Lane::LaneType::None ){
734  GenerateLaneMarksForCenterLine(road, lane_section, lane.second, inout, outinfo);
735  outinfo.push_back("yellow");
736  }
737  }
738  }
739  }
740  }
741 
743  const road::LaneSection& lane_section,
744  const road::Lane& lane,
745  std::vector<std::unique_ptr<Mesh>>& inout,
746  std::vector<std::string>& outinfo ) const {
747  Mesh out_mesh;
748  const double s_start = lane_section.GetDistance();
749  const double s_end = lane_section.GetDistance() + lane_section.GetLength();
750  double s_current = s_start;
751  std::vector<geom::Vector3D> vertices;
752  std::vector<size_t> indices;
753 
754  do {
755  //Get Lane info
757  if (road_info_mark != nullptr) {
758  carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
759 
760  switch (lane_mark_info.type) {
762  size_t currentIndex = out_mesh.GetVertices().size() + 1;
763 
764  std::pair<geom::Vector3D, geom::Vector3D> edges = lane.GetCornerPositions(s_current, 0);
765 
766  geom::Vector3D director = edges.second - edges.first;
767  director /= director.Length();
768  geom::Vector3D endmarking = edges.first + director * lane_mark_info.width;
769 
770  out_mesh.AddVertex(edges.first);
771  out_mesh.AddVertex(endmarking);
772 
773  out_mesh.AddIndex(currentIndex);
774  out_mesh.AddIndex(currentIndex + 1);
775  out_mesh.AddIndex(currentIndex + 2);
776 
777  out_mesh.AddIndex(currentIndex + 1);
778  out_mesh.AddIndex(currentIndex + 3);
779  out_mesh.AddIndex(currentIndex + 2);
780 
781  s_current += road_param.resolution;
782  break;
783  }
785  size_t currentIndex = out_mesh.GetVertices().size() + 1;
786 
787  std::pair<geom::Vector3D, geom::Vector3D> edges =
789 
790  geom::Vector3D director = edges.second - edges.first;
791  director /= director.Length();
792  geom::Vector3D endmarking = edges.first + director * lane_mark_info.width;
793 
794  out_mesh.AddVertex(edges.first);
795  out_mesh.AddVertex(endmarking);
796 
797  s_current += road_param.resolution * 3;
798  if (s_current > s_end)
799  {
800  s_current = s_end;
801  }
802  edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
803 
804  director = edges.second - edges.first;
805  director /= director.Length();
806  endmarking = edges.first + director * lane_mark_info.width;
807 
808  out_mesh.AddVertex(edges.first);
809  out_mesh.AddVertex(endmarking);
810 
811  out_mesh.AddIndex(currentIndex);
812  out_mesh.AddIndex(currentIndex + 1);
813  out_mesh.AddIndex(currentIndex + 2);
814 
815  out_mesh.AddIndex(currentIndex + 1);
816  out_mesh.AddIndex(currentIndex + 3);
817  out_mesh.AddIndex(currentIndex + 2);
818 
819  s_current += road_param.resolution * 3;
820 
821  break;
822  }
824  s_current += road_param.resolution;
825  break;
826  }
828  s_current += road_param.resolution;
829  break;
830  }
832  s_current += road_param.resolution;
833  break;
834  }
836  s_current += road_param.resolution;
837  break;
838  }
840  s_current += road_param.resolution;
841  break;
842  }
844  s_current += road_param.resolution;
845  break;
846  }
848  s_current += road_param.resolution;
849  break;
850  }
852  s_current += road_param.resolution;
853  break;
854  }
855  default: {
856  s_current += road_param.resolution;
857  break;
858  }
859  }
860  }
861  } while (s_current < s_end);
862 
863  if (out_mesh.IsValid()) {
865  if (road_info_mark != nullptr) {
866  carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
867  std::pair<geom::Vector3D, geom::Vector3D> edges = lane.GetCornerPositions(s_end, 0);
868  geom::Vector3D director = edges.second - edges.first;
869  director /= director.Length();
870  geom::Vector3D endmarking = edges.first + director * lane_mark_info.width;
871 
872  out_mesh.AddVertex(edges.first);
873  out_mesh.AddVertex(endmarking);
874  }
875  inout.push_back(std::make_unique<Mesh>(out_mesh));
876  }
877  }
878 
880  const road::Road& road,
881  const road::LaneSection& lane_section,
882  const road::Lane& lane,
883  std::vector<std::unique_ptr<Mesh>>& inout,
884  std::vector<std::string>& outinfo ) const
885  {
886  Mesh out_mesh;
887  const double s_start = lane_section.GetDistance();
888  const double s_end = lane_section.GetDistance() + lane_section.GetLength();
889  double s_current = s_start;
890  std::vector<geom::Vector3D> vertices;
891  std::vector<size_t> indices;
892 
893  do {
894  //Get Lane info
896  if (road_info_mark != nullptr) {
897  carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
898 
899  switch (lane_mark_info.type) {
901  size_t currentIndex = out_mesh.GetVertices().size() + 1;
902 
903  carla::road::element::DirectedPoint rightpoint = road.GetDirectedPointIn(s_current);
904  carla::road::element::DirectedPoint leftpoint = rightpoint;
905 
906  rightpoint.ApplyLateralOffset(lane_mark_info.width * 0.5);
907  leftpoint.ApplyLateralOffset(lane_mark_info.width * -0.5);
908 
909  // Unreal's Y axis hack
910  rightpoint.location.y *= -1;
911  leftpoint.location.y *= -1;
912 
913  out_mesh.AddVertex(rightpoint.location);
914  out_mesh.AddVertex(leftpoint.location);
915 
916  out_mesh.AddIndex(currentIndex);
917  out_mesh.AddIndex(currentIndex + 1);
918  out_mesh.AddIndex(currentIndex + 2);
919 
920  out_mesh.AddIndex(currentIndex + 1);
921  out_mesh.AddIndex(currentIndex + 3);
922  out_mesh.AddIndex(currentIndex + 2);
923 
924  s_current += road_param.resolution;
925  break;
926  }
928  size_t currentIndex = out_mesh.GetVertices().size() + 1;
929 
930  std::pair<geom::Vector3D, geom::Vector3D> edges =
932 
933  geom::Vector3D director = edges.second - edges.first;
934  director /= director.Length();
935  geom::Vector3D endmarking = edges.first + director * lane_mark_info.width;
936 
937  out_mesh.AddVertex(edges.first);
938  out_mesh.AddVertex(endmarking);
939 
940  s_current += road_param.resolution * 3;
941  if (s_current > s_end) {
942  s_current = s_end;
943  }
944 
945  edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
946 
947  director = edges.second - edges.first;
948  director /= director.Length();
949  endmarking = edges.first + director * lane_mark_info.width;
950 
951  out_mesh.AddVertex(edges.first);
952  out_mesh.AddVertex(endmarking);
953 
954  out_mesh.AddIndex(currentIndex);
955  out_mesh.AddIndex(currentIndex + 1);
956  out_mesh.AddIndex(currentIndex + 2);
957 
958  out_mesh.AddIndex(currentIndex + 1);
959  out_mesh.AddIndex(currentIndex + 3);
960  out_mesh.AddIndex(currentIndex + 2);
961 
962  s_current += road_param.resolution * 3;
963 
964  break;
965  }
967  s_current += road_param.resolution;
968  break;
969  }
971  s_current += road_param.resolution;
972  break;
973  }
975  s_current += road_param.resolution;
976  break;
977  }
979  s_current += road_param.resolution;
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  }
998  default: {
999  s_current += road_param.resolution;
1000  break;
1001  }
1002  }
1003  }
1004  } while (s_current < s_end);
1005 
1006  if (out_mesh.IsValid()) {
1008  if (road_info_mark != nullptr)
1009  {
1010  carla::road::element::LaneMarking lane_mark_info(*road_info_mark);
1011  carla::road::element::DirectedPoint rightpoint = road.GetDirectedPointIn(s_current);
1012  carla::road::element::DirectedPoint leftpoint = rightpoint;
1013 
1014  rightpoint.ApplyLateralOffset(lane_mark_info.width * 0.5f);
1015  leftpoint.ApplyLateralOffset(lane_mark_info.width * -0.5f);
1016 
1017  // Unreal's Y axis hack
1018  rightpoint.location.y *= -1;
1019  leftpoint.location.y *= -1;
1020 
1021  out_mesh.AddVertex(rightpoint.location);
1022  out_mesh.AddVertex(leftpoint.location);
1023 
1024  }
1025  inout.push_back(std::make_unique<Mesh>(out_mesh));
1026  }
1027  }
1028 
1029  struct VertexWeight {
1031  double weight;
1032  };
1035  std::vector<VertexWeight> neighbors;
1036  };
1037  struct VertexInfo {
1041  };
1042 
1043  // Helper function to compute the weight of neighboring vertices
1046  const VertexInfo &vertex_info,
1047  const VertexInfo &neighbor_info) {
1048  const float distance3D = geom::Math::Distance(*vertex_info.vertex, *neighbor_info.vertex);
1049  // Ignore vertices beyond a certain distance
1050  if(distance3D > road_param.max_weight_distance) {
1051  return {neighbor_info.vertex, 0};
1052  }
1053  if(abs(distance3D) < EPSILON) {
1054  return {neighbor_info.vertex, 0};
1055  }
1056  float weight = geom::Math::Clamp<float>(1.0f / distance3D, 0.0f, 100000.0f);
1057 
1058  // Additional weight to vertices in the same lane
1059  if(vertex_info.lane_mesh_idx == neighbor_info.lane_mesh_idx) {
1060  weight *= road_param.same_lane_weight_multiplier;
1061  // Further additional weight for fixed verices
1062  if(neighbor_info.is_static) {
1063  weight *= road_param.lane_ends_multiplier;
1064  }
1065  }
1066  return {neighbor_info.vertex, weight};
1067  }
1068 
1069  // Helper function to compute neighborhoord of vertices and their weights
1070  std::vector<VertexNeighbors> GetVertexNeighborhoodAndWeights(
1072  std::vector<std::unique_ptr<Mesh>> &lane_meshes) {
1073  // Build rtree for neighborhood queries
1075  using Point = Rtree::BPoint;
1076  Rtree rtree;
1077  for (size_t lane_mesh_idx = 0; lane_mesh_idx < lane_meshes.size(); ++lane_mesh_idx) {
1078  auto& mesh = lane_meshes[lane_mesh_idx];
1079  for(size_t i = 0; i < mesh->GetVerticesNum(); ++i) {
1080  auto& vertex = mesh->GetVertices()[i];
1081  Point point(vertex.x, vertex.y, vertex.z);
1082  if (i < 2 || i >= mesh->GetVerticesNum() - 2) {
1083  rtree.InsertElement({point, {&vertex, lane_mesh_idx, true}});
1084  } else {
1085  rtree.InsertElement({point, {&vertex, lane_mesh_idx, false}});
1086  }
1087  }
1088  }
1089 
1090  // Find neighbors for each vertex and compute their weight
1091  std::vector<VertexNeighbors> vertices_neighborhoods;
1092  for (size_t lane_mesh_idx = 0; lane_mesh_idx < lane_meshes.size(); ++lane_mesh_idx) {
1093  auto& mesh = lane_meshes[lane_mesh_idx];
1094  for(size_t i = 0; i < mesh->GetVerticesNum(); ++i) {
1095  if (i > 2 && i < mesh->GetVerticesNum() - 2) {
1096  auto& vertex = mesh->GetVertices()[i];
1097  Point point(vertex.x, vertex.y, vertex.z);
1098  auto closest_vertices = rtree.GetNearestNeighbours(point, 20);
1099  VertexNeighbors vertex_neighborhood;
1100  vertex_neighborhood.vertex = &vertex;
1101  for(auto& close_vertex : closest_vertices) {
1102  auto &vertex_info = close_vertex.second;
1103  if(&vertex == vertex_info.vertex) {
1104  continue;
1105  }
1106  auto vertex_weight = ComputeVertexWeight(
1107  road_param, {&vertex, lane_mesh_idx, false}, vertex_info);
1108  if(vertex_weight.weight > 0)
1109  vertex_neighborhood.neighbors.push_back(vertex_weight);
1110  }
1111  vertices_neighborhoods.push_back(vertex_neighborhood);
1112  }
1113  }
1114  }
1115  return vertices_neighborhoods;
1116  }
1117 
1118  std::unique_ptr<Mesh> MeshFactory::MergeAndSmooth(std::vector<std::unique_ptr<Mesh>> &lane_meshes) const {
1119  geom::Mesh out_mesh;
1120 
1121  auto vertices_neighborhoods = GetVertexNeighborhoodAndWeights(road_param, lane_meshes);
1122 
1123  // Laplacian function
1124  auto Laplacian = [&](const Mesh::vertex_type* vertex, const std::vector<VertexWeight> &neighbors) -> double {
1125  double sum = 0;
1126  double sum_weight = 0;
1127  for(auto &element : neighbors) {
1128  sum += (element.vertex->z - vertex->z)*element.weight;
1129  sum_weight += element.weight;
1130  }
1131  if(sum_weight > 0)
1132  return sum / sum_weight;
1133  else
1134  return 0;
1135  };
1136  // Run iterative algorithm
1137  double lambda = 0.5;
1138  int iterations = 100;
1139  for(int iter = 0; iter < iterations; ++iter) {
1140  for (auto& vertex_neighborhood : vertices_neighborhoods) {
1141  auto * vertex = vertex_neighborhood.vertex;
1142  vertex->z += static_cast<float>(lambda*Laplacian(vertex, vertex_neighborhood.neighbors));
1143  }
1144  }
1145 
1146  for(auto &mesh : lane_meshes) {
1147  out_mesh += *mesh;
1148  }
1149 
1150  return std::make_unique<Mesh>(out_mesh);
1151  }
1152 
1153 
1154 } // namespace geom
1155 } // namespace carla
void GenerateLaneMarksForNotCenterLine(const road::LaneSection &lane_section, const road::Lane &lane, std::vector< std::unique_ptr< Mesh >> &inout, std::vector< std::string > &outinfo) const
static auto Distance(const Vector3D &a, const Vector3D &b)
Definition: Math.h:78
LaneType GetType() const
Definition: Lane.cpp:38
Seting for map generation from opendrive without additional geometry.
void AddVertex(vertex_type vertex)
Appends a vertex to the vertices list.
Definition: Mesh.cpp:89
double GetDistance() const
Definition: LaneSection.cpp:13
static VertexWeight ComputeVertexWeight(const MeshFactory::RoadParameters &road_param, const VertexInfo &vertex_info, const VertexInfo &neighbor_info)
bool IsValid() const
Check if the mesh can be valid or not.
Definition: Mesh.cpp:20
std::unique_ptr< Mesh > Generate(const road::Road &road) const
Generates a mesh that defines a road.
Definition: MeshFactory.cpp:34
std::unique_ptr< Mesh > GenerateSidewalk(const road::LaneSection &lane_section) const
Each lane within a road cross section can be provided with several road markentries.
bgi::rtree< SpatialTreeEntry, bgi::rstar< 16 > > Rtree
Definition: InMemoryMap.h:58
void AddIndex(index_type index)
Appends a index to the indexes list.
Definition: Mesh.cpp:101
std::unique_ptr< Mesh > MergeAndSmooth(std::vector< std::unique_ptr< Mesh >> &lane_meshes) const
bool IsJunction() const
Definition: Road.cpp:42
std::vector< VertexNeighbors > GetVertexNeighborhoodAndWeights(const MeshFactory::RoadParameters &road_param, std::vector< std::unique_ptr< Mesh >> &lane_meshes)
double GetDistance() const
Definition: Lane.cpp:46
double GetLength() const
Definition: Lane.cpp:51
void GenerateAllOrderedWithMaxLen(const road::Road &road, std::map< road::Lane::LaneType, std::vector< std::unique_ptr< Mesh >>> &roads) const
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.
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:133
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.
void AddVertices(const std::vector< vertex_type > &vertices)
Appends a vertex to the vertices list.
Definition: Mesh.cpp:93
Mesh::vertex_type * vertex
double GetLength() const
Definition: LaneSection.cpp:17
float Length() const
Definition: geom/Vector3D.h:49
void AddUVs(const std::vector< uv_type > &uv)
Appends uvs.
Definition: Mesh.cpp:109
geom::Vector3D Vector3D
Definition: rpc/Vector3D.h:14
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
#define DEBUG_ASSERT(predicate)
Definition: Debug.h:66
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
auto GetLaneSections() const
Definition: Road.h:127
RoadParameters road_param
Definition: MeshFactory.h:149
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.
#define RELEASE_ASSERT(pred)
Definition: Debug.h:84
LaneType
Can be used as flags.
Definition: Lane.h:29
MeshFactory(rpc::OpendriveGenerationParameters params=rpc::OpendriveGenerationParameters())
Definition: MeshFactory.cpp:21
std::vector< VertexWeight > neighbors
void AddTriangleStrip(const std::vector< vertex_type > &vertices)
Adds a triangle strip to the mesh, vertex order is counterclockwise.
Definition: Mesh.cpp:47
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.
Mesh data container, validator and exporter.
Definition: Mesh.h:44
const T * GetInfo(const double s) const
Definition: Lane.h:79
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.
static constexpr double MESH_EPSILON
Definition: MeshFactory.cpp:32
std::map< LaneId, Lane > & GetLanes()
Definition: LaneSection.cpp:47
bool IsStraight() const
Checks whether the geometry is straight or not.
Definition: Lane.cpp:67
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::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. ...
std::vector< std::unique_ptr< Mesh > > GenerateAllWithMaxLen(const road::Road &road) const
Generates a chunked road with all the features needed for simulation.
static constexpr double EPSILON
We use this epsilon to shift the waypoints away from the edges of the lane sections to avoid floating...
Definition: MeshFactory.cpp:31
void GenerateLaneMarkForRoad(const road::Road &road, std::vector< std::unique_ptr< Mesh >> &inout, std::vector< std::string > &outinfo) const
Parameters for the road generation.
Definition: MeshFactory.h:137
Mesh::vertex_type * vertex
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.
const std::vector< vertex_type > & GetVertices() const
Definition: Mesh.cpp:255
Rtree class working with 3D point clouds.
Definition: Rtree.h:30
Mesh::vertex_type * vertex
void ApplyLateralOffset(float lateral_offset)
Definition: Geometry.cpp:28
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
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
LaneId GetId() const
Definition: Lane.cpp:34