opendrive_road.cpp 22.9 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
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
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
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
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++;
  }
}

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)
        new_path.push_back(this->nodes.size());
    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]);
        delete *lane_it;
        lane_it=this->lanes.erase(lane_it);
      }
      else
        lane_it++;
    }
    else
      lane_it++;
  }

  // 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)
428
429
430
431
432
433
434
435
436
437
438
439
440
{
  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;
}

441
COpendriveRoadNode* COpendriveRoad::get_node_at(TOpendriveWorldPoint &pose)
442
443
444
445
446
447
448
449
450
451
452
453
454
{
  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;
}

455

456
457
458
459
460
461
462
void COpendriveRoad::load(const std::string &filename)
{
  struct stat buffer;

  if(stat(filename.c_str(),&buffer)==0)
  {
    // delete any previous data
463
    this->free();
464
465
466
467
468
    // 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)
      {
469
        try{
470
          COpendriveRoadSegment *segment=new COpendriveRoadSegment();
471
472
          segment->set_resolution(this->resolution);
          segment->set_scale_factor(this->scale_factor);
473
474
          segment->set_min_road_length(this->min_road_length);
          segment->set_parent_road(this);
475
476
477
478
479
          segment->load(*road_it);
          this->segments.push_back(segment);
        }catch(CException &e){
          std::cout << e.what() << std::endl;
        }
480
      }
481
482
483
      // link segments
      this->link_segments(*open_drive);
      // process junctions
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
    }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);
}

504
double COpendriveRoad::get_resolution(void) const
505
506
507
508
509
510
511
512
513
514
515
516
517
{
  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);
}

518
double COpendriveRoad::get_scale_factor(void) const
519
520
521
522
523
524
525
{
  return this->scale_factor;
}

void COpendriveRoad::set_min_road_length(double length)
{
  this->min_road_length=length;
526
527
528

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

531
double COpendriveRoad::get_min_road_length(void) const
532
533
534
535
{
  return this->min_road_length;
}

536
unsigned int COpendriveRoad::get_num_segments(void) const
537
538
539
540
{
  return this->segments.size();
}

541
const COpendriveRoadSegment& COpendriveRoad::get_segment(unsigned int index) const
542
543
544
545
546
547
548
{
  if(index>=0 && index<this->segments.size())
    return *this->segments[index];
  else
    throw CException(_HERE_,"Invalid segment index");
}

549
550
551
552
553
554
555
556
557
558
559
560
561
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");
}

562
563
564
565
566
567
568
569
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
570

571
unsigned int COpendriveRoad::get_closest_node(TOpendriveWorldPoint &point,double angle_tol)
Sergi Hernandez's avatar
Sergi Hernandez committed
572
573
{
  double dist,min_dist=std::numeric_limits<double>::max();
574
  TOpendriveWorldPoint closest_point;
Sergi Hernandez's avatar
Sergi Hernandez committed
575
576
577
578
  unsigned int closest_index;

  for(unsigned int i=0;i<this->nodes.size();i++)
  { 
579
580
    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
581
582
583
584
585
586
587
588
589
590
    if(dist<min_dist)
    { 
      min_dist=dist;
      closest_index=i;
    }
  }

  return closest_index;
}

591
double COpendriveRoad::get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol)
592
593
{
  double dist,min_dist=std::numeric_limits<double>::max();
594
  TOpendriveWorldPoint point_found;
595
596
597
598
  double length,closest_length;

  for(unsigned int i=0;i<this->nodes.size();i++)
  {
599
600
    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
601
    if(dist<min_dist)
602
    {
Sergi Hernandez's avatar
Sergi Hernandez committed
603
      min_dist=dist;
604
      closest_point=point_found;
Sergi Hernandez's avatar
Sergi Hernandez committed
605
      closest_length=length;
606
607
608
609
610
611
    }
  }

  return closest_length;
}

612
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
613
614
615
616
617
618
619
620
{
  std::vector<TOpendriveWorldPoint> points;
  std::vector<double> lengths;

  closest_points.clear();
  closest_lengths.clear();
  for(unsigned int i=0;i<this->nodes.size();i++)
  {
621
    this->nodes[i]->get_closest_points(point,points,lengths,dist_tol,angle_tol);
Sergi Hernandez's avatar
Sergi Hernandez committed
622
623
624
625
626
627
628
629
    for(unsigned int j=0;j<points.size();i++)
    {
      closest_points.push_back(points[i]);
      closest_lengths.push_back(lengths[i]);
    }
  }
}

630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
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
717
718
719
720
721
void COpendriveRoad::get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPoint &start_point,TOpendriveWorldPoint &end_point,COpendriveRoad &new_road)
{
  segment_up_ref_t new_segment_ref;
  lane_up_ref_t new_lane_ref;
  node_up_ref_t new_node_ref;
  COpendriveRoadNode *node,*next_node;
  COpendriveRoadSegment *segment,*new_segment;
  std::vector<unsigned int> new_path_nodes;
  unsigned int link_index;
  int node_side;
  bool added;

  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);
          new_segment=segment->get_sub_segment(new_node_ref,new_lane_ref,node_side,&start_point,NULL);
        }
        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;
    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;
  }
  new_road.update_references(new_segment_ref,new_lane_ref,new_node_ref);
  // 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);
  new_road.clean_references(new_segment_ref,new_lane_ref,new_node_ref);
}

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

}

722
723
void COpendriveRoad::operator=(const COpendriveRoad& object)
{
724
725
  COpendriveRoadSegment *segment;
  COpendriveRoadNode *node;
726
727
728
729
  COpendriveLane *lane;
  segment_up_ref_t new_segment_ref;
  node_up_ref_t new_node_ref;
  lane_up_ref_t new_lane_ref;
730

731
  this->free();
732
733
734
  this->resolution=object.resolution;
  this->scale_factor=object.scale_factor;
  this->min_road_length=object.min_road_length;
735
  for(unsigned int i=0;i<object.lanes.size();i++)
736
  {
737
738
739
    lane=new COpendriveLane(*object.lanes[i]);
    this->lanes.push_back(lane);
    new_lane_ref[object.lanes[i]]=lane;
740
  }
741

742
743
744
745
  for(unsigned int i=0;i<object.nodes.size();i++)
  {
    node=new COpendriveRoadNode(*object.nodes[i]);
    this->nodes.push_back(node);
746
    new_node_ref[object.nodes[i]]=node;
747
  }
748
749
750
751
752
753
754
755

  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
756
757
758
759
}

std::ostream& operator<<(std::ostream& out, COpendriveRoad &road)
{
760
761
762
  out << "Resolution: " << road.resolution << std::endl;
  out << "Scale factor: " << road.scale_factor << std::endl;
  out << "Minimum road lenght: " << road.min_road_length << std::endl;
763
  out << "Total number of nodes: " << road.nodes.size() << std::endl;
764
  for(unsigned int i=0;i<road.segments.size();i++)
765
    std::cout << *road.segments[i];
766
767
768
769
770
771

  return out;
}

COpendriveRoad::~COpendriveRoad()
{
772
  this->free();
773
774
775
776
777
  this->resolution=DEFAULT_RESOLUTION;
  this->scale_factor=DEFAULT_SCALE_FACTOR;
  this->min_road_length=DEFAULT_MIN_ROAD_LENGTH;
}