From c0588a170946caef1c975cc72e8f9ea56a64c96a Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Thu, 23 Apr 2020 15:13:21 +0200
Subject: [PATCH] Access to more useful information

---
 include/open_drive_format.h             | 16 +++++++
 src/examples/open_drive_format_test.cpp |  2 -
 src/open_drive_format.cpp               | 57 +++++++++++++++++++++++--
 3 files changed, 69 insertions(+), 6 deletions(-)

diff --git a/include/open_drive_format.h b/include/open_drive_format.h
index de3c9ca..05cbb24 100644
--- a/include/open_drive_format.h
+++ b/include/open_drive_format.h
@@ -9,6 +9,22 @@ typedef struct
   int id; ///< Projection polynomial of radially symmetric model.
 }Road_struct;
 
+// UNMARKEDINTERSECTION 102
+// STOPANDGIVEWAY 206
+// PARKINGAREA ???
+// HAVEWAY ???
+// AHEADONLY 209
+// AHEADONLYSUB 30
+// GIVEWAY 205
+// PEDESTRIANCROSSING ???
+// ROUNDABOUT ???
+// NOOVERTAKING 276
+// NOENTRYVEHICULARTRAFFIC 267
+// TESTCOURSEA9 ???
+// ONEWAYSTREET 220
+// ROADWORKS 123
+// KMH50 274
+// KMH100 274
 
 class COpenDriveFormat
 {
diff --git a/src/examples/open_drive_format_test.cpp b/src/examples/open_drive_format_test.cpp
index d8cd950..80a9390 100644
--- a/src/examples/open_drive_format_test.cpp
+++ b/src/examples/open_drive_format_test.cpp
@@ -5,8 +5,6 @@
 int main(int argc, char *argv[])
 {
   COpenDriveFormat open_drive_format;
-  // std::string xml_file = "../src/xml/Crossing8Course.xodr";
-  // std::string xml_file = "../src/xml/CrossingComplex8Course.xodr";
   std::string xml_file = "../src/xml/atlatec_generic.xodr";
   // std::string xml_file = "../src/xml/atlatec_vires.xodr";
   try
diff --git a/src/open_drive_format.cpp b/src/open_drive_format.cpp
index 9c7745c..44c78df 100644
--- a/src/open_drive_format.cpp
+++ b/src/open_drive_format.cpp
@@ -9,10 +9,7 @@
 #include <sstream> 
 
 #ifdef _HAVE_XSD
-// #include "xml/OpenDRIVE_1.1.hxx"
-// #include "xml/OpenDRIVE_1.5M.hxx"
 #include "xml/OpenDRIVE_1.4H.hxx"
-// #include "xml/OpenDRIVE_1.4H.h"
 #endif
 
 COpenDriveFormat::COpenDriveFormat()
@@ -29,6 +26,7 @@ void COpenDriveFormat::load(std::string &filename)
     try{
       std::auto_ptr<OpenDRIVE> open_drive(OpenDRIVE_(filename.c_str(), xml_schema::flags::dont_validate));
 
+      ////////////////// Access road atributes
       for (OpenDRIVE::road_iterator road_it(open_drive->road().begin()); road_it != open_drive->road().end(); ++road_it)
       {
         // Road_struct r;
@@ -37,7 +35,12 @@ void COpenDriveFormat::load(std::string &filename)
         // r.id = road_it->id().get();
         // this->road_vect.push_back(r);
 
-        std::cout << "Road id = " << road_it->id().get() << std::endl;
+        
+        std::cout << "Road: id = " << road_it->id().get();
+        std::cout << ", length = " << road_it->length().get();
+        std::cout << ", junction = " << road_it->junction().get() << std::endl;
+
+        ///////////////////// link atributes
         if (road_it->lane_link().present())
         {
           if (road_it->lane_link().get().predecessor().present())
@@ -53,6 +56,51 @@ void COpenDriveFormat::load(std::string &filename)
             std::cout << "; contact point: " << (road_it->lane_link().get().successor().get().contactPoint().present() ? road_it->lane_link().get().successor().get().contactPoint().get() : "") << std::endl;
           }
         }
+
+        //////////////// Geometry atributes
+        for (planView::geometry_iterator geo_it(road_it->planView().geometry().begin()); geo_it != road_it->planView().geometry().end(); ++geo_it)
+        {
+          std::cout << "  Geometry: From s = " << (geo_it->s().present() ? geo_it->s().get() : 0.0); 
+          std::cout << " to s = " << (geo_it->length().present() ? geo_it->length().get() : 0.0) << std::endl;
+          std::cout << "    Origin pose: x = " << (geo_it->x().present() ? geo_it->x().get() : 0.0); 
+          std::cout << "; y = " << (geo_it->y().present() ? geo_it->y().get() : 0.0); 
+          std::cout << "; heading = " << (geo_it->hdg().present() ? geo_it->hdg().get() : 0.0) << std::endl;
+
+          if (geo_it->line().present())
+          {
+            std::cout << "    type: Line" <<  std::endl;
+          }
+          else if (geo_it->spiral().present())
+          {
+            std::cout << "    type: Spiral-> curvStart = " << (geo_it->spiral().get().curvStart().present() ? geo_it->spiral().get().curvStart().get() : 0.0);
+            std::cout << ",  curvEnd = " << (geo_it->spiral().get().curvEnd().present() ? geo_it->spiral().get().curvEnd().get() : 0.0) << std::endl;
+          }
+          else if (geo_it->arc().present())
+          {
+            std::cout << "    type: Arc-> curvature = " << (geo_it->arc().get().curvature().present() ? geo_it->arc().get().curvature().get() : 0.0) <<  std::endl;
+          }
+          else if (geo_it->poly3().present())
+          {
+            std::cout << "    type: Poly3-> a = " << (geo_it->poly3().get().a().present() ? geo_it->poly3().get().a().get() : 0.0);
+            std::cout << ", b = " << (geo_it->poly3().get().b().present() ? geo_it->poly3().get().b().get() : 0.0);
+            std::cout << ", c = " << (geo_it->poly3().get().c().present() ? geo_it->poly3().get().c().get() : 0.0);
+            std::cout << ", d = " << (geo_it->poly3().get().d().present() ? geo_it->poly3().get().d().get() : 0.0) <<  std::endl;
+          }
+          else if (geo_it->paramPoly3().present())
+          {
+            std::cout << "    type: ParamPoly3-> aU = " << (geo_it->paramPoly3().get().aU().present() ? geo_it->paramPoly3().get().aU().get() : 0.0);
+            std::cout << ", bU = " << (geo_it->paramPoly3().get().bU().present() ? geo_it->paramPoly3().get().bU().get() : 0.0);
+            std::cout << ", cU = " << (geo_it->paramPoly3().get().cU().present() ? geo_it->paramPoly3().get().cU().get() : 0.0);
+            std::cout << ", dU = " << (geo_it->paramPoly3().get().dU().present() ? geo_it->paramPoly3().get().dU().get() : 0.0) <<  std::endl;
+            std::cout << "                    -> aV = " << (geo_it->paramPoly3().get().aV().present() ? geo_it->paramPoly3().get().aV().get() : 0.0);
+            std::cout << ", bV = " << (geo_it->paramPoly3().get().bV().present() ? geo_it->paramPoly3().get().bV().get() : 0.0);
+            std::cout << ", cV = " << (geo_it->paramPoly3().get().cV().present() ? geo_it->paramPoly3().get().cV().get() : 0.0);
+            std::cout << ", dV = " << (geo_it->paramPoly3().get().dV().present() ? geo_it->paramPoly3().get().dV().get() : 0.0) <<  std::endl;
+            std::cout << "                    -> pRange = " << (geo_it->paramPoly3().get().pRange().present() ? geo_it->paramPoly3().get().pRange().get() : 0.0) <<  std::endl;
+          }
+        }
+
+        ////////// Signals atributes
         if (road_it->signals().present())
         {
           for (signals::signal_iterator signal_it(road_it->signals().get().signal().begin()); signal_it != road_it->signals().get().signal().end(); ++signal_it)
@@ -71,6 +119,7 @@ void COpenDriveFormat::load(std::string &filename)
 
           }
         }
+        std::cout << std::endl;
       }
       // road->header()
       std::cout << "Done." << std::endl;
-- 
GitLab