opendrive_road.cpp 25.5 KB
Newer Older
1
#include "opendrive_road.h"
2
#include "exceptions.h"
3
4
#include <sys/types.h>
#include <sys/stat.h>
5
#include <math.h>
6
7
8
9
10
11
12

COpendriveRoad::COpendriveRoad()
{
  this->resolution=DEFAULT_RESOLUTION;
  this->scale_factor=DEFAULT_SCALE_FACTOR;
  this->min_road_length=DEFAULT_MIN_ROAD_LENGTH;
  this->segments.clear();
13
  this->nodes.clear();
14
  this->lanes.clear();
15
16
17
18
19
}

COpendriveRoad::COpendriveRoad(const COpendriveRoad& object)
{
  COpendriveRoadSegment *segment;
20
  COpendriveRoadNode *node;
21
22
23
24
  COpendriveLane *lane;
  segment_up_ref_t new_segment_ref;
  node_up_ref_t new_node_ref;
  lane_up_ref_t new_lane_ref;
25

26
  this->free();
27
28
29
  this->resolution=object.resolution;
  this->scale_factor=object.scale_factor;
  this->min_road_length=object.min_road_length;
30
31
32
33
34
35
  for(unsigned int i=0;i<object.lanes.size();i++)
  {
    lane=new COpendriveLane(*object.lanes[i]);
    this->lanes.push_back(lane);
    new_lane_ref[object.lanes[i]]=lane;
  }
36
37
38
39
  for(unsigned int i=0;i<object.nodes.size();i++)
  {
    node=new COpendriveRoadNode(*object.nodes[i]);
    this->nodes.push_back(node);
40
    new_node_ref[object.nodes[i]]=node;
41
  }
42
43
  for(unsigned int i=0;i<object.segments.size();i++)
  {
44
    segment=new COpendriveRoadSegment(*object.segments[i]);
45
46
47
48
    this->segments.push_back(segment);
    new_segment_ref[object.segments[i]]=segment;
  }
  // update references
49
50
}

51
52
53
54
55
56
57
58
59
60
61
COpendriveRoadSegment &COpendriveRoad::operator[](std::string &key)
{
  for(unsigned int i=0;i<this->segments.size();i++)
  {
    if(this->segments[i]->get_id()==(unsigned int)std::stoi(key))
      return *this->segments[i];
  }

  throw CException(_HERE_,"No road segment with the given ID");
}

62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
void COpendriveRoad::free(void)
{
  for(unsigned int i=0;i<this->segments.size();i++)
  {
    delete this->segments[i];
    this->segments[i]=NULL;
  }
  this->segments.clear();
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
    delete this->nodes[i];
    this->nodes[i]=NULL;
  }
  this->nodes.clear();
  for(unsigned int i=0;i<this->lanes.size();i++)
  {
    delete this->lanes[i];
    this->lanes[i]=NULL;
  }
  this->lanes.clear();
}

84
85
void COpendriveRoad::link_segments(OpenDRIVE &open_drive)
{
86
  std::string predecessor_id,successor_id;
87
  std::string predecessor_contact,successor_contact;
88

89
90
  for(OpenDRIVE::road_iterator road_it(open_drive.road().begin());road_it!=open_drive.road().end();++road_it)
  {
91
92
93
94
    // get current segment
    COpendriveRoadSegment &road=(*this)[road_it->id().get()];
    // get predecessor and successor
    if(road_it->lane_link().present())
95
    {
96
      if(road_it->lane_link().get().predecessor().present())// predecessor present
97
      {
98
        if(road_it->lane_link().get().predecessor().get().elementType().get()=="road")// previous segment is a road
99
        {
100
          predecessor_id=road_it->lane_link().get().predecessor().get().elementId().get();
101
102
          predecessor_contact=road_it->lane_link().get().predecessor().get().contactPoint().get();
        }
103
104
105
106
      }
      if(road_it->lane_link().get().successor().present())// successor present
      {
        if(road_it->lane_link().get().successor().get().elementType().get()=="road")
107
        {
108
          successor_id=road_it->lane_link().get().successor().get().elementId().get();
109
110
          successor_contact=road_it->lane_link().get().successor().get().contactPoint().get();
        }
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
      }
    }
    if(std::stoi(road_it->junction().get())==-1)// non junction road segments
    {
      if(!predecessor_id.empty())
      {
        COpendriveRoadSegment &prev_road=(*this)[predecessor_id];
        prev_road.link_segment(road);
        predecessor_id.clear();
      }
      if(!successor_id.empty())
      {
        COpendriveRoadSegment &next_road=(*this)[successor_id];
        road.link_segment(next_road);
        successor_id.clear();
      }
    }
    else// junction segment
    {
      for(OpenDRIVE::junction_iterator junction_it(open_drive.junction().begin());junction_it!=open_drive.junction().end();++junction_it)
      {
        for(junction::connection_iterator connection_it(junction_it->connection().begin()); connection_it!=junction_it->connection().end();++connection_it)
133
        {
134
135
136
137
138
139
140
141
142
143
144
          std::string incoming_road_id;
          std::string connecting_road_id;
          if(connection_it->incomingRoad().present())
            incoming_road_id=connection_it->incomingRoad().get();
          else
            throw CException(_HERE_,"Connectivity information missing");
          if(connection_it->connectingRoad().present())
            connecting_road_id=connection_it->connectingRoad().get();
          else
            throw CException(_HERE_,"Connectivity information missing");
          if(predecessor_id.compare(incoming_road_id)==0 && successor_id.compare(connecting_road_id)==0)// this is the connection
145
          {
146
147
148
149
150
151
152
153
154
155
156
157
158
159
            COpendriveRoadSegment &prev_road=(*this)[predecessor_id];
            COpendriveRoadSegment &next_road=(*this)[successor_id];
            for(connection::laneLink_iterator lane_link_it(connection_it->laneLink().begin()); lane_link_it!=connection_it->laneLink().end();++lane_link_it)
            {
              int from_lane_id;
              int to_lane_id;
              if(lane_link_it->from().present())
                from_lane_id=lane_link_it->from().get();
              else
                throw CException(_HERE_,"Connectivity information missing");
              if(lane_link_it->to().present())
                to_lane_id=lane_link_it->to().get();
              else
                throw CException(_HERE_,"Connectivity information missing");
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
              if(predecessor_contact=="end")
                prev_road.link_segment(road,from_lane_id,false,-1,true);
              else 
                prev_road.link_segment(road,from_lane_id,true,-1,true);
              TOpendriveWorldPoint end=road.get_lane(-1).get_end_point();
              if(successor_contact=="end")
              {
                TOpendriveWorldPoint start=next_road.get_lane(to_lane_id).get_end_point();
                if(fabs(end.x-start.x)<this->resolution && fabs(end.y-start.y)<this->resolution)
                  road.link_segment(next_road,-1,false,to_lane_id,false);
              }
              else
              {
                TOpendriveWorldPoint start=next_road.get_lane(to_lane_id).get_start_point();
                if(fabs(end.x-start.x)<this->resolution && fabs(end.y-start.y)<this->resolution)
                  road.link_segment(next_road,-1,false,to_lane_id,true);
              }
177
            }
178
179
180
181
182
183
184
          }
        }
      }
    }
  }
}

185
unsigned int COpendriveRoad::add_node(COpendriveRoadNode *node)
186
187
188
189
190
191
192
{
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
    if(this->nodes[i]==node)
      throw CException(_HERE_,"Node already present");
  }
  this->nodes.push_back(node);
193
194

  return this->nodes.size()-1;
195
196
}

197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
void COpendriveRoad::remove_node(COpendriveRoadNode *node)
{
  std::vector<COpendriveRoadNode *>::iterator it;

  for(it=this->nodes.begin();it!=this->nodes.end();)
  {
    if((*it)->get_index()==node->get_index())
    {
      delete *it;
      it=this->nodes.erase(it);
      break;
    }
    else
      it++;
  }
}

unsigned int COpendriveRoad::add_lane(COpendriveLane *lane)
{
  for(unsigned int i=0;i<this->lanes.size();i++)
  {
    if(this->lanes[i]==lane)
      throw CException(_HERE_,"Lane already present");
  }
  this->lanes.push_back(lane);

  return this->lanes.size()-1;
}

void COpendriveRoad::remove_lane(COpendriveLane *lane)
{
  std::vector<COpendriveLane *>::iterator it;

  for(it=this->lanes.begin();it!=this->lanes.end();)
  {
    if((*it)->get_index()==lane->get_index())
    {
      delete *it;
      it=this->lanes.erase(it);
      break;
    }
    else
      it++;
  }
}

243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
void COpendriveRoad::complete_open_lanes(void)
{
  std::vector<COpendriveLane *>::iterator lane_it;
  COpendriveRoadNode *new_node;
  TOpendriveWorldPoint end_point;
  unsigned int new_node_index;

  // remove all nodes and lanes not present in the path
  for(lane_it=this->lanes.begin();lane_it!=this->lanes.end();)
  {
    if((*lane_it)->next.empty())// lane is not connected
    {
      if((*lane_it)->get_id()<0)
        end_point=(*lane_it)->get_end_point();
      else
        end_point=(*lane_it)->get_start_point();
      if(!this->node_exists_at(end_point))// there is no node at the end point
      {
        new_node=new COpendriveRoadNode();
        new_node->set_resolution(this->resolution);
        new_node->set_scale_factor(this->scale_factor);
        new_node->set_start_point(end_point);
        new_node_index=this->add_node(new_node);
        new_node->set_index(new_node_index);
        (*lane_it)->add_node(new_node);
        (*lane_it)->segment->add_node(new_node);
      }
      else
        lane_it++;
    }
    else
      lane_it++;
  }   
}

278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
void COpendriveRoad::add_segment(COpendriveRoadSegment *segment,std::vector<unsigned int> &old_path,std::vector<unsigned int> &new_path)
{
  for(unsigned int i=0;i<this->segments.size();i++)
    if(this->segments[i]->get_id()==segment->get_id())// segment is already present
      return;
  // add the new segment
  this->segments.push_back(segment);
  // add the lanes
  for(unsigned int i=1;i<=segment->get_num_right_lanes();i++)
  {
    segment->lanes[-i]->set_index(this->lanes.size());
    this->lanes.push_back(segment->lanes[-i]);
  }
  for(unsigned int i=1;i<=segment->get_num_left_lanes();i++)
  {
    segment->lanes[i]->set_index(this->lanes.size());
    this->lanes.push_back(segment->lanes[i]);
  }
  // add the nodes
  for(unsigned int i=0;i<segment->get_num_nodes();i++)
  {
    for(unsigned int j=0;j<old_path.size();j++)
      if(old_path[j]==segment->nodes[i]->index)
301
        new_path[j]=this->nodes.size();
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
    segment->nodes[i]->set_index(this->nodes.size());
    this->nodes.push_back(segment->nodes[i]);
  }
}

void COpendriveRoad::update_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs)
{
  std::vector<COpendriveRoadSegment *>::iterator seg_it;
  std::vector<COpendriveLane *>::iterator lane_it;
  std::vector<COpendriveRoadNode *>::iterator node_it;

  for(seg_it=this->segments.begin();seg_it!=this->segments.end();seg_it++)
  {
    if(segment_refs.find(*seg_it)!=segment_refs.end())
    {
      (*seg_it)=segment_refs[*seg_it];
      (*seg_it)->update_references(segment_refs,lane_refs,node_refs);
    }
    else if((*seg_it)->updated(segment_refs))
      (*seg_it)->update_references(segment_refs,lane_refs,node_refs);
  }
  for(lane_it=this->lanes.begin();lane_it!=this->lanes.end();lane_it++)
    if(lane_refs.find(*lane_it)!=lane_refs.end())
      (*lane_it)=lane_refs[*lane_it];
  for(node_it=this->nodes.begin();node_it!=this->nodes.end();node_it++)
    if(node_refs.find(*node_it)!=node_refs.end())
      (*node_it)=node_refs[*node_it];
}

void COpendriveRoad::clean_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs)
{
  std::vector<COpendriveRoadSegment *>::iterator seg_it;
  std::vector<COpendriveLane *>::iterator lane_it;
  std::vector<COpendriveRoadNode *>::iterator node_it;

  for(seg_it=this->segments.begin();seg_it!=this->segments.end();)
  {
    if(segment_refs.find(*seg_it)!=segment_refs.end())
    {
      (*seg_it)=segment_refs[*seg_it];
      (*seg_it)->clean_references(segment_refs,lane_refs,node_refs);
      seg_it++;
    }
    else if((*seg_it)->updated(segment_refs))
    {
      (*seg_it)->clean_references(segment_refs,lane_refs,node_refs);
      seg_it++;
    }
    else
      seg_it=this->segments.erase(seg_it);
  }
  for(lane_it=this->lanes.begin();lane_it!=this->lanes.end();)
  {
    if(lane_refs.find(*lane_it)!=lane_refs.end())
    {
      (*lane_it)=lane_refs[*lane_it];
      lane_it++;
    }
    else if(!(*lane_it)->updated(lane_refs))
      lane_it=this->lanes.erase(lane_it);
    else
      lane_it++;
  }
  for(node_it=this->nodes.begin();node_it!=this->nodes.end();)
  {
    if(node_refs.find(*node_it)!=node_refs.end())
    {
      (*node_it)=node_refs[*node_it];
      node_it++;
    }
    else if(!(*node_it)->updated(node_refs))
      node_it=this->nodes.erase(node_it);
    else
      node_it++;
  }
}

void COpendriveRoad::prune(std::vector<unsigned int> &path_nodes)
{
  COpendriveLane *neightbour_lane;
  std::vector<COpendriveLane *>::iterator lane_it;
  bool present;

  // remove all nodes and lanes not present in the path
  for(lane_it=this->lanes.begin();lane_it!=this->lanes.end();)
  {
    present=false;
    for(unsigned int i=0;i<path_nodes.size();i++)
    {
      if((*lane_it)->has_node(path_nodes[i]))
      {
        present=true;
        break;
      }
    } 
    if(!present)
    {
      neightbour_lane=(*lane_it)->left_lane;
      while(neightbour_lane!=NULL)
      {
        for(unsigned int i=0;i<path_nodes.size();i++)
        {
          if(neightbour_lane->has_node(path_nodes[i]))
          {
            present=true;
            break;
          }
        }
        if(present)
          break;
        neightbour_lane=neightbour_lane->left_lane;
      }
      neightbour_lane=(*lane_it)->right_lane;
      while(neightbour_lane!=NULL)
      {
        for(unsigned int i=0;i<path_nodes.size();i++)
        {
          if(neightbour_lane->has_node(path_nodes[i]))
          {
            present=true;
            break;
          }
        }
        if(present)
          break;
        neightbour_lane=neightbour_lane->right_lane;
      }
      if(!present)
      {
        (*lane_it)->segment->remove_lane(*lane_it);
        for(unsigned int i=0;i<(*lane_it)->nodes.size();i++)
          this->remove_node((*lane_it)->nodes[i]);
        lane_it=this->lanes.erase(lane_it);
      }
      else
        lane_it++;
    }
    else
      lane_it++;
  }
442
443
444
445
446
447
448
449
450
451
  // re-index all nodes and the path
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
    for(unsigned int j=0;j<path_nodes.size();j++)
    {
      if(this->nodes[i]->get_index()==path_nodes[j])
        path_nodes[j]=i;
    }
    this->nodes[i]->set_index(i);
  }
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471

  // remove links to non-consecutive nodes
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
    for(unsigned int j=0;j<this->nodes[i]->get_num_links();j++)
    {
      for(unsigned int k=0;k<path_nodes.size()-1;k++)
      {
        if(path_nodes[k]==this->nodes[i]->links[j]->prev->index)
          if(path_nodes[k+1]!=this->nodes[i]->links[j]->next->index)
          {
            this->nodes[i]->remove_link(this->nodes[i]->links[j]);
            break;
          }
      }
    }
  } 
}

bool COpendriveRoad::node_exists_at(TOpendriveWorldPoint &pose)
472
473
474
475
476
477
478
479
480
481
482
483
484
{
  TOpendriveWorldPoint node_pose;

  for(unsigned int i=0;i<nodes.size();i++)
  {
    node_pose=this->nodes[i]->get_start_pose();
    if(std::abs(pose.x-node_pose.x)<0.01 && std::abs(pose.y-node_pose.y)<0.01)
      return true;
  }

  return false;
}

485
COpendriveRoadNode* COpendriveRoad::get_node_at(TOpendriveWorldPoint &pose)
486
487
488
489
490
491
492
493
494
495
496
497
498
{
  TOpendriveWorldPoint node_pose;

  for(unsigned int i=0;i<nodes.size();i++)
  {
    node_pose=this->nodes[i]->get_start_pose();
    if(std::abs(pose.x-node_pose.x)<0.01 && std::abs(pose.y-node_pose.y)<0.01)
      return this->nodes[i];
  }

  return NULL;
}

499

500
501
502
503
504
505
506
void COpendriveRoad::load(const std::string &filename)
{
  struct stat buffer;

  if(stat(filename.c_str(),&buffer)==0)
  {
    // delete any previous data
507
    this->free();
508
509
510
511
512
    // try to open the specified file
    try{
      std::unique_ptr<OpenDRIVE> open_drive(OpenDRIVE_(filename.c_str(), xml_schema::flags::dont_validate));
      for (OpenDRIVE::road_iterator road_it(open_drive->road().begin()); road_it != open_drive->road().end(); ++road_it)
      {
513
        try{
514
          COpendriveRoadSegment *segment=new COpendriveRoadSegment();
515
516
          segment->set_resolution(this->resolution);
          segment->set_scale_factor(this->scale_factor);
517
518
          segment->set_min_road_length(this->min_road_length);
          segment->set_parent_road(this);
519
520
521
522
523
          segment->load(*road_it);
          this->segments.push_back(segment);
        }catch(CException &e){
          std::cout << e.what() << std::endl;
        }
524
      }
525
526
527
      // link segments
      this->link_segments(*open_drive);
      // process junctions
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
    }catch (const xml_schema::exception& e){
      std::ostringstream os;
      os << e;
      /* handle exceptions */
      throw CException(_HERE_,os.str());
    }
  }
  else
    throw CException(_HERE_,"The .xodr file does not exist");
}

void COpendriveRoad::set_resolution(double res)
{
  this->resolution=res;

  // change the resolution of all current nodes
  for(unsigned int i=0;i<this->segments.size();i++)
    this->segments[i]->set_resolution(res);
}

548
double COpendriveRoad::get_resolution(void) const
549
550
551
552
553
554
555
556
557
558
559
560
561
{
  return this->resolution;
}

void COpendriveRoad::set_scale_factor(double scale)
{
  this->scale_factor=scale;

  // change the resolution of all current nodes
  for(unsigned int i=0;i<this->segments.size();i++)
    this->segments[i]->set_scale_factor(scale);
}

562
double COpendriveRoad::get_scale_factor(void) const
563
564
565
566
567
568
569
{
  return this->scale_factor;
}

void COpendriveRoad::set_min_road_length(double length)
{
  this->min_road_length=length;
570
571
572

  for(unsigned int i=0;i<this->segments.size();i++)
    this->segments[i]->set_min_road_length(length);
573
574
}

575
double COpendriveRoad::get_min_road_length(void) const
576
577
578
579
{
  return this->min_road_length;
}

580
unsigned int COpendriveRoad::get_num_segments(void) const
581
582
583
584
{
  return this->segments.size();
}

585
const COpendriveRoadSegment& COpendriveRoad::get_segment(unsigned int index) const
586
587
588
589
590
591
592
{
  if(index>=0 && index<this->segments.size())
    return *this->segments[index];
  else
    throw CException(_HERE_,"Invalid segment index");
}

593
594
595
596
597
598
599
600
601
602
603
604
605
unsigned int COpendriveRoad::get_num_nodes(void) const
{
  return this->nodes.size();
}

const COpendriveRoadNode& COpendriveRoad::get_node(unsigned int index) const
{
  if(index>=0 && index<this->nodes.size())
    return *this->nodes[index];
  else
    throw CException(_HERE_,"Invalid node index");
}

606
607
608
609
610
611
612
613
const COpendriveRoadSegment& COpendriveRoad::operator[](std::size_t index)
{
  if(index>=0 && index<this->segments.size())
    return *this->segments[index];
  else
    throw CException(_HERE_,"Invalid segment index");
}

Sergi Hernandez's avatar
Sergi Hernandez committed
614

615
unsigned int COpendriveRoad::get_closest_node(TOpendriveWorldPoint &point,double angle_tol)
Sergi Hernandez's avatar
Sergi Hernandez committed
616
617
{
  double dist,min_dist=std::numeric_limits<double>::max();
618
  TOpendriveWorldPoint closest_point;
Sergi Hernandez's avatar
Sergi Hernandez committed
619
620
621
622
  unsigned int closest_index;

  for(unsigned int i=0;i<this->nodes.size();i++)
  { 
623
624
    this->nodes[i]->get_closest_point(point,closest_point,angle_tol);
    dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
Sergi Hernandez's avatar
Sergi Hernandez committed
625
626
627
628
629
630
631
632
633
634
    if(dist<min_dist)
    { 
      min_dist=dist;
      closest_index=i;
    }
  }

  return closest_index;
}

635
double COpendriveRoad::get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol)
636
637
{
  double dist,min_dist=std::numeric_limits<double>::max();
638
  TOpendriveWorldPoint point_found;
639
640
641
642
  double length,closest_length;

  for(unsigned int i=0;i<this->nodes.size();i++)
  {
643
644
    length=this->nodes[i]->get_closest_point(point,point_found,angle_tol);
    dist=sqrt(pow(point_found.x-point.x,2.0)+pow(point_found.y-point.y,2.0));
Sergi Hernandez's avatar
Sergi Hernandez committed
645
    if(dist<min_dist)
646
    {
Sergi Hernandez's avatar
Sergi Hernandez committed
647
      min_dist=dist;
648
      closest_point=point_found;
Sergi Hernandez's avatar
Sergi Hernandez committed
649
      closest_length=length;
650
651
652
653
654
655
    }
  }

  return closest_length;
}

656
void COpendriveRoad::get_closest_points(TOpendriveWorldPoint &point,std::vector<TOpendriveWorldPoint> &closest_points,std::vector<double> &closest_lengths,double dist_tol,double angle_tol)
Sergi Hernandez's avatar
Sergi Hernandez committed
657
658
659
660
661
662
663
664
{
  std::vector<TOpendriveWorldPoint> points;
  std::vector<double> lengths;

  closest_points.clear();
  closest_lengths.clear();
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
665
    this->nodes[i]->get_closest_points(point,points,lengths,dist_tol,angle_tol);
Sergi Hernandez's avatar
Sergi Hernandez committed
666
667
668
669
670
671
672
673
    for(unsigned int j=0;j<points.size();i++)
    {
      closest_points.push_back(points[i]);
      closest_lengths.push_back(lengths[i]);
    }
  }
}

674
std::vector<unsigned int> COpendriveRoad::get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPoint &start_point,TOpendriveWorldPoint &end_point,COpendriveRoad &new_road)
675
676
677
678
{
  segment_up_ref_t new_segment_ref;
  lane_up_ref_t new_lane_ref;
  node_up_ref_t new_node_ref;
679
680
  COpendriveRoadNode *node,*next_node,*repeat_node,*repeat_next_node;
  COpendriveRoadSegment *segment,*new_segment,*repeat_segment;
681
682
  std::vector<unsigned int> new_path_nodes;
  unsigned int link_index;
683
  bool added,repeated;
684
  int node_side;
685
686

  new_path_nodes.resize(path_nodes.size());
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716

  new_road.free();
  new_road.set_resolution(this->resolution);
  new_road.set_scale_factor(this->scale_factor);
  new_road.set_min_road_length(this->min_road_length);

  if(path_nodes.size()==1)
  {
    node=this->nodes[path_nodes[path_nodes.size()-1]];
    link_index=node->get_closest_link(end_point);
    segment=node->links[link_index]->segment;
    node_side=segment->get_node_side(node);
    new_segment=segment->get_sub_segment(new_node_ref,new_lane_ref,node_side,&start_point,&end_point);
    new_road.add_segment(new_segment,path_nodes,new_path_nodes);
    new_segment_ref[segment]=new_segment;
  }
  else
  {
    for(unsigned int i=0;i<path_nodes.size()-1;i++)
    {
      node=this->nodes[path_nodes[i]];
      next_node=this->nodes[path_nodes[i+1]];
      segment=node->get_link_with(next_node)->segment;
      if(segment->has_node(next_node))
        continue;
      else
      {
        if(i==0)
        {
          node_side=segment->get_node_side(node);
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
          repeated=false;
          for(unsigned int j=1;j<path_nodes.size();j++)
          {
            repeat_node=this->nodes[path_nodes[j]];
            if(j==path_nodes.size()-1)
            {
              link_index=node->get_closest_link(end_point,3.14159);
              repeat_segment=node->links[link_index]->segment;
            }
            else
            {
              repeat_next_node=this->nodes[path_nodes[j+1]];
              repeat_segment=repeat_node->get_link_with(repeat_next_node)->segment;
            }
            if(segment==repeat_segment)
            {
              repeated=true;
              break;
            }
          }
          if(repeated)
            new_segment=segment->clone(new_node_ref,new_lane_ref);
          else
            new_segment=segment->get_sub_segment(new_node_ref,new_lane_ref,node_side,&start_point,NULL);
741
742
743
744
745
746
747
748
749
750
751
        }
        else
          new_segment=segment->clone(new_node_ref,new_lane_ref);
        new_road.add_segment(new_segment,path_nodes,new_path_nodes);
        new_segment_ref[segment]=new_segment;
      }
    }
    // add the last segment
    node=this->nodes[path_nodes[path_nodes.size()-1]];
    link_index=node->get_closest_link(end_point,3.14159);
    segment=node->links[link_index]->segment;
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
    repeated=false;
    for(unsigned int j=0;j<path_nodes.size()-1;j++)
    {
      repeat_node=this->nodes[path_nodes[j]];
      repeat_next_node=this->nodes[path_nodes[j+1]];
      repeat_segment=repeat_node->get_link_with(repeat_next_node)->segment;
      if(segment==repeat_segment)
      {
        repeated=true;
        break;
      }
    }
    if(!repeated)
    {
      node_side=segment->get_node_side(node);
      new_segment=segment->get_sub_segment(new_node_ref,new_lane_ref,node_side,NULL,&end_point);
      new_road.add_segment(new_segment,path_nodes,new_path_nodes);
      new_segment_ref[segment]=new_segment;
    }
771
772
  }
  new_road.update_references(new_segment_ref,new_lane_ref,new_node_ref);
773
  new_road.clean_references(new_segment_ref,new_lane_ref,new_node_ref);
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
  // add additional nodes not explicitly in the path
/*
  for(unsigned int i=0;i<path_nodes.size();i++)
  {
    added=false;
    node=this->nodes[path_nodes[i]];
    for(unsigned int j=i+1;j<path_nodes.size();j++)
    {
      next_node=this->nodes[path_nodes[j]];
      for(unsigned int k=0;k<this->segments.size();k++)
        if(this->segments[k]->connects_nodes(node,next_node))
        {
          new_segment=this->segments[k]->clone(new_node_ref,new_lane_ref);
          new_road.add_segment(new_segment,path_nodes,new_path_nodes);
          new_segment_ref[segment]=new_segment;
          added=true;
          break;
        }
      if(added)
        break;
    }
  }
*/
  // remove unconnected elements
  new_road.prune(new_path_nodes);
799
800
801
  new_road.complete_open_lanes();

  return new_path_nodes;
802
803
804
805
806
807
808
}

void COpendriveRoad::get_sub_road(TOpendriveWorldPoint &start_point,double length,COpendriveRoad &road)
{

}

809
810
void COpendriveRoad::operator=(const COpendriveRoad& object)
{
811
812
  COpendriveRoadSegment *segment;
  COpendriveRoadNode *node;
813
814
815
816
  COpendriveLane *lane;
  segment_up_ref_t new_segment_ref;
  node_up_ref_t new_node_ref;
  lane_up_ref_t new_lane_ref;
817

818
  this->free();
819
820
821
  this->resolution=object.resolution;
  this->scale_factor=object.scale_factor;
  this->min_road_length=object.min_road_length;
822
  for(unsigned int i=0;i<object.lanes.size();i++)
823
  {
824
825
826
    lane=new COpendriveLane(*object.lanes[i]);
    this->lanes.push_back(lane);
    new_lane_ref[object.lanes[i]]=lane;
827
  }
828

829
830
831
832
  for(unsigned int i=0;i<object.nodes.size();i++)
  {
    node=new COpendriveRoadNode(*object.nodes[i]);
    this->nodes.push_back(node);
833
    new_node_ref[object.nodes[i]]=node;
834
  }
835
836
837
838
839
840
841
842

  for(unsigned int i=0;i<object.segments.size();i++)
  {
    segment=new COpendriveRoadSegment(*object.segments[i]);
    this->segments.push_back(segment);
    new_segment_ref[object.segments[i]]=segment;
  }
  // update references
843
844
845
846
}

std::ostream& operator<<(std::ostream& out, COpendriveRoad &road)
{
847
848
849
  out << "Resolution: " << road.resolution << std::endl;
  out << "Scale factor: " << road.scale_factor << std::endl;
  out << "Minimum road lenght: " << road.min_road_length << std::endl;
850
  out << "Total number of nodes: " << road.nodes.size() << std::endl;
851
  for(unsigned int i=0;i<road.segments.size();i++)
852
    std::cout << *road.segments[i];
853
854
855
856
857
858

  return out;
}

COpendriveRoad::~COpendriveRoad()
{
859
  this->free();
860
861
862
863
864
  this->resolution=DEFAULT_RESOLUTION;
  this->scale_factor=DEFAULT_SCALE_FACTOR;
  this->min_road_length=DEFAULT_MIN_ROAD_LENGTH;
}