diff --git a/include/opendrive_road.h b/include/opendrive_road.h index b8c9a28e090ff63d84fb231f994e4f71bcb0f1ac..e2607d3182efac8bcc30c067a0cbe6ecb37b238e 100644 --- a/include/opendrive_road.h +++ b/include/opendrive_road.h @@ -20,10 +20,9 @@ class COpendriveRoad protected: COpendriveRoadSegment &operator[](std::string &key); void link_segments(OpenDRIVE &open_drive); - void add_node(COpendriveRoadNode *node); + unsigned int add_node(COpendriveRoadNode *node); bool node_exists_at(const TOpendriveWorldPoint &pose); COpendriveRoadNode* get_node_at(const TOpendriveWorldPoint &pose) const; - std::string get_junction_road_id(OpenDRIVE &open_drive,std::string &incoming,std::string &connecting); public: COpendriveRoad(); COpendriveRoad(const COpendriveRoad& object); diff --git a/src/examples/opendrive_test.cpp b/src/examples/opendrive_test.cpp index 8764f9b0d4538ce3d416b7d53ec4fa49693bc104..77de2727849d4c4707a77396efd85e1935686531 100644 --- a/src/examples/opendrive_test.cpp +++ b/src/examples/opendrive_test.cpp @@ -7,7 +7,7 @@ int main(int argc, char *argv[]) { COpendriveRoad road; - std::string xml_file="/home/shernand/iri-lab/adc_ws/code/autonomous_driving_tools/src/xml/adc_road.xodr"; + std::string xml_file="/home/shernand/iri-lab/adc_ws/code/autonomous_driving_tools/src/xml/add_road_full.xodr"; try { diff --git a/src/opendrive_road_segment.cpp b/src/opendrive_road_segment.cpp index 911130c5114af79c8bb9ef872e8ff2a3b263b573..3eab20a8e0569ca566981483c64eedb42d9799e1 100644 --- a/src/opendrive_road_segment.cpp +++ b/src/opendrive_road_segment.cpp @@ -165,6 +165,7 @@ void COpendriveRoadSegment::add_nodes(OpenDRIVE::road_type &road_info) COpendriveRoadNode *new_node; TOpendriveWorldPoint node_pose; double lane_offset; + unsigned int index; try{ for(geom_it=road_info.planView().geometry().begin(); geom_it!=road_info.planView().geometry().end(); ++geom_it) @@ -187,7 +188,11 @@ void COpendriveRoadSegment::add_nodes(OpenDRIVE::road_type &road_info) new_node->add_lane(*geom_it,this->lanes[i]); } else - this->parent_road->add_node(new_node); + { + index=this->parent_road->add_node(new_node); + new_node->set_index(index); + new_node->set_parent_segment(this); + } this->lanes[i]->add_node(new_node); lane_offset-=this->lanes[i]->get_width(); } @@ -214,7 +219,11 @@ void COpendriveRoadSegment::add_nodes(OpenDRIVE::road_type &road_info) new_node->add_lane(*geom_it,this->lanes[i]); } else - this->parent_road->add_node(new_node); + { + index=this->parent_road->add_node(new_node); + new_node->set_index(index); + new_node->set_parent_segment(this); + } this->lanes[i]->add_node(new_node); lane_offset+=this->lanes[i]->get_width(); } @@ -250,13 +259,13 @@ void COpendriveRoadSegment::link_neightbour_lanes(lanes::laneSection_type &lane_ center_mark=OD_MARK_SOLID; else if(center_lane.roadMark().begin()->type1().get()=="broken") center_mark=OD_MARK_BROKEN; - else if(center_lane.roadMark().begin()->type1().get()=="solid_solid") + else if(center_lane.roadMark().begin()->type1().get()=="solid solid") center_mark=OD_MARK_SOLID_SOLID; - else if(center_lane.roadMark().begin()->type1().get()=="solid_broken") + else if(center_lane.roadMark().begin()->type1().get()=="solid broken") center_mark=OD_MARK_SOLID_BROKEN; - else if(center_lane.roadMark().begin()->type1().get()=="broken_solid") + else if(center_lane.roadMark().begin()->type1().get()=="broken solid") center_mark=OD_MARK_BROKEN_SOLID; - else if(center_lane.roadMark().begin()->type1().get()=="broken_broken") + else if(center_lane.roadMark().begin()->type1().get()=="broken broken") center_mark=OD_MARK_BROKEN_BROKEN; else center_mark=OD_MARK_NONE; @@ -332,17 +341,37 @@ void COpendriveRoadSegment::link_segment(COpendriveRoadSegment &segment) void COpendriveRoadSegment::link_segment(COpendriveRoadSegment &segment,int from, int to) { + bool connect=true; + for(unsigned int i=0;i<this->connecting.size();i++) + { if(this->connecting[i]->get_id()==segment.get_id())// the segment is already included - return; - for(unsigned int i=0;i<segment.connecting.size();i++) - if(segment.connecting[i]->get_id()==this->id) - return; - this->connecting.push_back(&segment); - segment.connecting.push_back(this); + { + for(unsigned int j=0;j<segment.connecting.size();j++) + { + if(segment.connecting[j]->get_id()==this->id) + { + connect=false; + break; + } + } + } + } + if(connect) + { + this->connecting.push_back(&segment); + segment.connecting.push_back(this); + } // link lanes - if(this->lanes.find(from)!=this->lanes.end() && segment.lanes.find(to)!=segment.lanes.end()) - this->lanes[from]->link_lane(segment.lanes[to],OD_MARK_NONE); + if(segment.lanes.find(to)!=segment.lanes.end()) + { + if(this->lanes.find(from-1)!=this->lanes.end()) + this->lanes[from-1]->link_lane(segment.lanes[to],this->lanes[from-1]->right_mark); + if(this->lanes.find(from)!=this->lanes.end()) + this->lanes[from]->link_lane(segment.lanes[to],OD_MARK_NONE); + if(this->lanes.find(from+1)!=this->lanes.end()) + this->lanes[from+1]->link_lane(segment.lanes[to],this->lanes[from+1]->left_mark); + } } void COpendriveRoadSegment::load(OpenDRIVE::road_type &road_info)