From 3bc53ffcf137dc29655bfbf6713177d66175f6d6 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Thu, 3 Dec 2020 17:34:33 +0100
Subject: [PATCH] Initial commit of the library to import Opendrive roads.

---
 include/opendrive_arc.h          |    24 +
 include/opendrive_common.h       |    40 +
 include/opendrive_geometry.h     |    36 +
 include/opendrive_lane.h         |    41 +
 include/opendrive_line.h         |    22 +
 include/opendrive_link.h         |    44 +
 include/opendrive_object.h       |    68 +
 include/opendrive_param_poly3.h  |    36 +
 include/opendrive_road.h         |    37 +
 include/opendrive_road_node.h    |    36 +
 include/opendrive_road_segment.h |    51 +
 include/opendrive_signal.h       |    34 +
 include/opendrive_spiral.h       |    26 +
 src/CMakeLists.txt               |    17 +-
 src/examples/CMakeLists.txt      |     5 +
 src/examples/opendrive_test.cpp  |    25 +
 src/opendrive_arc.cpp            |    65 +
 src/opendrive_common.cpp         |    29 +
 src/opendrive_geometry.cpp       |   103 +
 src/opendrive_lane.cpp           |   138 +
 src/opendrive_line.cpp           |    53 +
 src/opendrive_link.cpp           |   102 +
 src/opendrive_object.cpp         |   231 +
 src/opendrive_param_poly3.cpp    |   131 +
 src/opendrive_road.cpp           |   162 +
 src/opendrive_road_node.cpp      |   186 +
 src/opendrive_road_segment.cpp   |   289 +
 src/opendrive_signal.cpp         |   117 +
 src/opendrive_spiral.cpp         |    66 +
 src/xml/CMakeLists.txt           |    47 +
 src/xml/OpenDRIVE_1.4H.cxx       | 36361 +++++++++++++++++++++++++++++
 src/xml/OpenDRIVE_1.4H.hxx       | 15776 +++++++++++++
 src/xml/OpenDRIVE_1.4H.xsd       |  1284 +
 src/xml/adc_road.xodr            |   997 +
 34 files changed, 56676 insertions(+), 3 deletions(-)
 create mode 100644 include/opendrive_arc.h
 create mode 100644 include/opendrive_common.h
 create mode 100644 include/opendrive_geometry.h
 create mode 100644 include/opendrive_lane.h
 create mode 100644 include/opendrive_line.h
 create mode 100644 include/opendrive_link.h
 create mode 100644 include/opendrive_object.h
 create mode 100644 include/opendrive_param_poly3.h
 create mode 100644 include/opendrive_road.h
 create mode 100644 include/opendrive_road_node.h
 create mode 100644 include/opendrive_road_segment.h
 create mode 100644 include/opendrive_signal.h
 create mode 100644 include/opendrive_spiral.h
 create mode 100644 src/examples/opendrive_test.cpp
 create mode 100644 src/opendrive_arc.cpp
 create mode 100644 src/opendrive_common.cpp
 create mode 100644 src/opendrive_geometry.cpp
 create mode 100644 src/opendrive_lane.cpp
 create mode 100644 src/opendrive_line.cpp
 create mode 100644 src/opendrive_link.cpp
 create mode 100644 src/opendrive_object.cpp
 create mode 100644 src/opendrive_param_poly3.cpp
 create mode 100644 src/opendrive_road.cpp
 create mode 100644 src/opendrive_road_node.cpp
 create mode 100644 src/opendrive_road_segment.cpp
 create mode 100644 src/opendrive_signal.cpp
 create mode 100644 src/opendrive_spiral.cpp
 create mode 100644 src/xml/CMakeLists.txt
 create mode 100644 src/xml/OpenDRIVE_1.4H.cxx
 create mode 100644 src/xml/OpenDRIVE_1.4H.hxx
 create mode 100644 src/xml/OpenDRIVE_1.4H.xsd
 create mode 100644 src/xml/adc_road.xodr

diff --git a/include/opendrive_arc.h b/include/opendrive_arc.h
new file mode 100644
index 0000000..4b51b3a
--- /dev/null
+++ b/include/opendrive_arc.h
@@ -0,0 +1,24 @@
+#ifndef _OPENDRIVE_ARC_H
+#define _OPENDRIVE_ARC_H
+
+#include "opendrive_geometry.h"
+
+class COpendriveArc : public COpendriveGeometry
+{
+  private:
+    double curvature;
+  protected:
+    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    virtual void print(std::ostream &out);
+    virtual void load_params(const planView::geometry_type &geometry_info);
+  public:
+    COpendriveArc();
+    COpendriveArc(double min_s, double max_s, double x, double y, double heading, double curvature);
+    COpendriveArc(const COpendriveArc &object);
+    virtual COpendriveGeometry *clone(void);
+    double get_curvature(void);
+    void operator=(const COpendriveArc &object);
+    ~COpendriveArc();
+};
+
+#endif
diff --git a/include/opendrive_common.h b/include/opendrive_common.h
new file mode 100644
index 0000000..98915d0
--- /dev/null
+++ b/include/opendrive_common.h
@@ -0,0 +1,40 @@
+#ifndef _OPENDRIVE_COMMON_H
+#define _OPENDRIVE_COMMON_H
+
+#define DEFAULT_RESOLUTION        0.1
+#define DEFAULT_SCALE_FACTOR      1.0
+#define DEFAULT_MIN_ROAD_LENGTH   0.1
+
+typedef struct
+{
+  double s;
+  double t;
+  double heading;
+}TOpendriveTrackPoint;
+
+typedef struct
+{
+  double u;
+  double v;
+  double heading;
+}TOpendriveLocalPoint;
+
+typedef struct
+{
+  double x;
+  double y;
+  double heading;
+}TOpendriveWorldPoint;
+
+typedef enum{OD_MARK_NONE,
+             OD_MARK_SOLID,
+             OD_MARK_BROKEN,
+             OD_MARK_SOLID_SOLID,
+             OD_MARK_SOLID_BROKEN,
+             OD_MARK_BROKEN_SOLID,
+             OD_MARK_BROKEN_BROKEN} opendrive_mark_t;
+
+double normalize_angle(double angle);
+double diff_angle(double angle1,double angle2);
+
+#endif
diff --git a/include/opendrive_geometry.h b/include/opendrive_geometry.h
new file mode 100644
index 0000000..f88dfbb
--- /dev/null
+++ b/include/opendrive_geometry.h
@@ -0,0 +1,36 @@
+#ifndef _OPENDRIVE_GEOMETRY_H
+#define _OPENDRIVE_GEOMETRY_H
+
+#include "opendrive_common.h"
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+#include <iostream>
+
+class COpendriveGeometry
+{
+  private:
+  protected:
+    double min_s; ///< Starting track coordenate "s" for the geometry.
+    double max_s; ///< Ending track coordenate "s" for the geometry.
+    TOpendriveWorldPoint pose;
+    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) = 0;
+    virtual void print(std::ostream &out);
+    virtual void load_params(const planView::geometry_type &geometry_info) = 0;
+  public:
+    COpendriveGeometry();
+    COpendriveGeometry(double min_s, double max_s, double x, double y, double heading);
+    COpendriveGeometry(const COpendriveGeometry &object);
+    virtual COpendriveGeometry *clone(void) = 0;
+    void load(const planView::geometry_type &geometry_info);
+    bool get_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    bool get_world_pose(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world);
+    bool in_range(double s);
+    double get_length(void);
+    void operator=(const COpendriveGeometry &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveGeometry &geom);
+    virtual ~COpendriveGeometry();
+};
+
+#endif
diff --git a/include/opendrive_lane.h b/include/opendrive_lane.h
new file mode 100644
index 0000000..8914c6a
--- /dev/null
+++ b/include/opendrive_lane.h
@@ -0,0 +1,41 @@
+#ifndef _OPENDRIVE_LANE_H
+#define _OPENDRIVE_LANE_H
+
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+#include "opendrive_road_node.h"
+
+class COpendriveLane
+{
+  friend class COpendriveRoadSegment;
+  private:
+    std::vector<COpendriveRoadNode *> nodes;
+    COpendriveRoadSegment *segment;
+    double scale_factor;
+    double width;
+    double speed;
+    double offset;
+  protected:
+    void add_node(COpendriveRoadNode *node);
+    void set_resolution(double res);
+    void set_scale_factor(double scale);
+    void set_offset(double offset);
+    void update_references(std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> refs)
+  public:
+    COpendriveLane();
+    COpendriveLane(const COpendriveLane &object);
+    void load(const right::lane_type &lane_info,COpendriveRoadSegment *segment);
+    unsigned int get_num_nodes(void);
+    const COpendriveRoadNode &get_node(unsigned int index);
+    const COpendriveRoadSegment &get_segment(void);
+    double get_width(void);
+    double get_speed(void);
+    double get_offset(void);
+    void operator=(const COpendriveLane &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveLane &lane);
+    ~COpendriveLane();
+};
+
+#endif
diff --git a/include/opendrive_line.h b/include/opendrive_line.h
new file mode 100644
index 0000000..d9dd05f
--- /dev/null
+++ b/include/opendrive_line.h
@@ -0,0 +1,22 @@
+#ifndef _OPENDRIVE_LINE_H
+#define _OPENDRIVE_LINE_H
+
+#include "opendrive_geometry.h"
+
+class COpendriveLine : public COpendriveGeometry
+{
+  private:
+  protected:
+    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    virtual void print(std::ostream &out);
+    virtual void load_params(const planView::geometry_type &geometry_info);
+  public:
+    COpendriveLine();
+    COpendriveLine(double min_s, double max_s, double x, double y, double heading);
+    COpendriveLine(const COpendriveGeometry &object);
+    virtual COpendriveGeometry *clone(void);
+    void operator=(const COpendriveLine &object);
+    ~COpendriveLine();
+};
+
+#endif
diff --git a/include/opendrive_link.h b/include/opendrive_link.h
new file mode 100644
index 0000000..b89c14e
--- /dev/null
+++ b/include/opendrive_link.h
@@ -0,0 +1,44 @@
+#ifndef _OPNEDRIVE_LINK_H
+#define _OPENDRIVE_LINK_H
+
+#include "opendrive_road_node.h"
+#include "g2_spline.h"
+#include "opendrive_line.h"
+#include "opendrive_spiral.h"
+#include "opendrive_arc.h"
+#include "opendrive_param_poly3.h"
+
+class COpendriveLink
+{
+  private:
+    COpendriveRoadNode *prev;
+    COpendriveRoadNode *next;
+    CG2Spline *spline;
+    opendrive_mark_t mark;
+    double resolution;
+    double scale_factor;    
+  protected:
+    void set_prev(COpendriveRoadNode *node);
+    void set_next(COpendriveRoadNode *node);
+    void set_road_mark(opendrive_mark_t mark);
+    void set_resolution(double res);
+    void set_scale_factor(double scale);
+  public:
+    COpendriveLink();
+    COpendriveLink(const COpendriveLink &object);
+    const COpendriveRoadNode &get_prev(void);
+    const COpendriveRoadNode &get_next(void);
+    opendrive_mark_t get_road_mark(void);
+    double get_resolution(void);
+    double get_scale_factor(void);
+    double find_closest_world_point(TOpendriveWorldPoint &world,TPoint &point);
+    double find_closest_local_point(TOpendriveLocalPoint &local,TPoint &point);
+    double get_track_point_world(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world);
+    double get_track_point_local(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    double get_length(void);
+    void operator=(const COpendriveLink &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveLink &link);
+    ~COpendriveLink();
+};
+
+#endif
diff --git a/include/opendrive_object.h b/include/opendrive_object.h
new file mode 100644
index 0000000..ca8f6ae
--- /dev/null
+++ b/include/opendrive_object.h
@@ -0,0 +1,68 @@
+#ifndef _OPENDRIVE_OBJECT_H
+#define _OPENDRIVE_OBJECT_H
+
+#include "opendrive_common.h"
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+#define OD_MAX_VERTICES     32
+
+typedef enum {OD_NONE,OD_BOX,OD_CYLINDER,OD_POLYGON} object_type_t;
+
+typedef struct
+{
+  double length;
+  double width;
+  double height;
+}TOpendriveBox;
+
+typedef struct
+{
+  double radius;
+  double height;
+}TOpendriveCylinder;
+
+typedef struct
+{  
+  TOpendriveTrackPoint vertices[OD_MAX_VERTICES];
+  double height[OD_MAX_VERTICES];
+  unsigned int num_vertices;
+}TOpendrivePolygon;
+
+typedef union
+{
+  TOpendriveBox box;
+  TOpendriveCylinder cylinder;
+  TOpendrivePolygon polygon;
+}TOpendriveObject;
+
+class COpendriveObject
+{
+  private:
+    int id; ///< Object's id.
+    TOpendriveTrackPoint pose;
+    TOpendriveObject object;
+    std::string type; ///< Object's OpenDrive type.
+    std::string name; ///< Object's name.
+    object_type_t object_type;
+  protected:
+  public:
+    COpendriveObject();
+    COpendriveObject(const COpendriveObject& object);
+    void load(std::unique_ptr<objects::object_type> &object_info);
+    TOpendriveTrackPoint get_pose(void);
+    std::string get_type(void);
+    std::string get_name(void);
+    bool is_box(void);
+    bool is_cylinder(void);
+    bool is_polygon(void);
+    TOpendriveBox get_box_data(void);
+    TOpendriveCylinder get_cylinder_data(void);
+    TOpendrivePolygon get_polygon_data(void);
+    void operator=(const COpendriveObject &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveObject &object);
+    ~COpendriveObject();
+};
+
+#endif
diff --git a/include/opendrive_param_poly3.h b/include/opendrive_param_poly3.h
new file mode 100644
index 0000000..d366b85
--- /dev/null
+++ b/include/opendrive_param_poly3.h
@@ -0,0 +1,36 @@
+#ifndef _OPENDRIVE_PARAMPOLY3_H
+#define _OPENDRIVE_PARAMPOLY3_H
+
+#include "opendrive_geometry.h"
+
+typedef struct
+{
+  double a;
+  double b;
+  double c;
+  double d;
+}TOpendrivePoly3Params;
+
+class COpendriveParamPoly3 : public COpendriveGeometry
+{
+  private:
+    TOpendrivePoly3Params u;
+    TOpendrivePoly3Params v;
+    bool normalized;
+  protected:
+    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    virtual void print(std::ostream &out);
+    virtual void load_params(const planView::geometry_type &geometry_info);
+  public:
+    COpendriveParamPoly3();
+    COpendriveParamPoly3(double min_s, double max_s, double x, double y, double heading,TOpendrivePoly3Params &u,TOpendrivePoly3Params &v,bool normalized);
+    COpendriveParamPoly3(const COpendriveParamPoly3 &object);
+    virtual COpendriveGeometry *clone(void);
+    TOpendrivePoly3Params get_u_params(void);
+    TOpendrivePoly3Params get_v_params(void);
+    bool is_normalized(void);
+    void operator=(const COpendriveParamPoly3 &object);
+    ~COpendriveParamPoly3();
+};
+
+#endif
diff --git a/include/opendrive_road.h b/include/opendrive_road.h
new file mode 100644
index 0000000..efd6145
--- /dev/null
+++ b/include/opendrive_road.h
@@ -0,0 +1,37 @@
+#ifndef _OPENDRIVE_ROAD_H
+#define _OPENDRIVE_ROAD_H
+
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+#include "opendrive_road_segment.h"
+
+class COpendriveRoad
+{
+  private:
+    std::vector<COpendriveRoadSegment *> segments;
+    double resolution;
+    double scale_factor;
+    double min_road_length;
+  protected:
+    void add_road_nodes(std::unique_ptr<OpenDRIVE::road_type> &road_info);
+    void set_resolution(double res);
+    void set_scale_factor(double scale);
+    void set_min_road_length(double length);
+  public:
+    COpendriveRoad();
+    COpendriveRoad(const COpendriveRoad& object);
+    void load(const std::string &filename);
+    double get_resolution(void);
+    double get_scale_factor(void);
+    double get_min_road_length(void);
+    unsigned int get_num_segments(void);
+    const COpendriveRoadSegment& get_segment(unsigned int index);
+    const COpendriveRoadSegment& operator[](std::size_t index);
+    void operator=(const COpendriveRoad& object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveRoad &road);
+    ~COpendriveRoad();
+};
+
+#endif
diff --git a/include/opendrive_road_node.h b/include/opendrive_road_node.h
new file mode 100644
index 0000000..7b16a7f
--- /dev/null
+++ b/include/opendrive_road_node.h
@@ -0,0 +1,36 @@
+#ifndef _OPENDRIVE_ROAD_NODE_H
+#define _OPENDRIVE_ROAD_NODE_H
+
+#include <vector>
+#include "opendrive_link.h"
+#include "opendrive_lane.h"
+
+class COpendriveRoadNode
+{
+  private:
+    std::vector<COpendriveLink *> links;
+    double resolution;
+    double scale_factor;
+    TOpendriveWorldPoint start_point;
+    COpendriveLane *lane;
+    COpendriveGeometry *geometry;
+  protected:
+    unsigned int add_link(COpendriveRoadNode *node);
+    void set_resolution(double res);
+    void set_scale_factor(double scale);
+  public:
+    COpendriveRoadNode();
+    COpendriveRoadNode(const COpendriveRoadNode &object);
+    void load(const planView::geometry_type &node_info,COpendriveLane *lane);
+    double get_resolution(void);
+    double get_scale_factor(void);
+    TOpendriveWorldPoint get_start_pose(void);
+    unsigned int get_num_links(void);
+    const COpendriveLink &get_link(unsigned int index);
+    const COpendriveLane &get_lane(void);
+    void operator=(const COpendriveRoadNode &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveRoadNode &node);
+    ~COpendriveRoadNode();
+};
+
+#endif
diff --git a/include/opendrive_road_segment.h b/include/opendrive_road_segment.h
new file mode 100644
index 0000000..c66c649
--- /dev/null
+++ b/include/opendrive_road_segment.h
@@ -0,0 +1,51 @@
+#ifndef _OPENDRIVE_ROAD_SEGMENT_H
+#define _OPENDRIVE_ROAD_SEGMENT_H
+
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+#include "opendrive_lane.h"
+#include "opendrive_signal.h"
+#include "opendrive_object.h"
+
+class COpendriveRoadSegment
+{
+  friend class COpendriveRoad;
+  private:
+    std::map<int,COpendriveLane *> lanes;
+    unsigned int num_right_lanes;
+    unsigned int num_left_lanes;
+    std::vector<COpendriveSignal *> signals;
+    std::vector<COpendriveObject *> objects;
+    std::vector<COpendriveRoadSegment *> next;
+    std::vector<COpendriveRoadSegment *> prev;
+    std::string name;
+    unsigned int id;
+  protected:
+    void set_resolution(double res);
+    void set_scale_factor(double scale);
+    void update_references(std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> refs);
+  public:
+    COpendriveRoadSegment();
+    COpendriveRoadSegment(const COpendriveRoadSegment &object);
+    void load_road(OpenDRIVE::road_type &road_info);
+    std::string get_name(void);
+    unsigned int get_id(void);
+    unsigned int get_num_right_lanes(void);
+    unsigned int get_num_left_lanes(void);
+    const COpendriveLane &get_lane(int index);
+    unsigned int get_num_signals(void);
+    const COpendriveSignal &get_signal(unsigned int index);
+    unsigned int get_num_obstacles(void);
+    const COpendriveObject &get_object(unsigned int index);
+    unsigned int get_num_previous(void);
+    const COpendriveRoadSegment &get_previous(unsigned int index);
+    unsigned int get_num_next(void);
+    const COpendriveRoadSegment &get_next(unsigned int index);
+    void operator=(const COpendriveRoadSegment &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveRoadsegment &segment);
+    ~COpendriveRoadSegment();
+};
+
+#endif
diff --git a/include/opendrive_signal.h b/include/opendrive_signal.h
new file mode 100644
index 0000000..0704985
--- /dev/null
+++ b/include/opendrive_signal.h
@@ -0,0 +1,34 @@
+#ifndef _OPENDRIVE_SIGNAL_H
+#define _OPENDRIVE_SIGNAL_H
+
+#include "opendrive_common.h"
+#ifdef _HAVE_XSD
+#include "../src/xml/OpenDRIVE_1.4H.hxx"
+#endif
+
+class COpendriveSignal
+{
+  private:
+    int id; ///< Signal's id.
+    TOpendriveTrackPoint pose;
+    std::string type; ///< Signal's OpenDrive type.
+    std::string sub_type; ///< Signal's OpenDrive subtype.
+    int value; ///< Signal's value.
+    std::string text; ///< Signal's text.    
+  protected:
+  public:
+    COpendriveSignal();
+    COpendriveSignal(const COpendriveSignal &object);
+    COpendriveSignal(int id, double s, double t, double heading, std::string type, std::string sub_type, int value, std::string text, bool reverse = false);
+    void load(std::unique_ptr<signals::signal_type> &signal_info);
+    int get_id(void);
+    TOpendriveTrackPoint get_pose(void);
+    void get_type(std::string &type, std::string &sub_type);
+    int get_value(void);
+    std::string get_text(void);
+    void operator=(const COpendriveSignal &object);
+    friend std::ostream& operator<<(std::ostream& out, COpendriveSignal &signal);
+    ~COpendriveSignal();
+};
+
+#endif
diff --git a/include/opendrive_spiral.h b/include/opendrive_spiral.h
new file mode 100644
index 0000000..05c2a9f
--- /dev/null
+++ b/include/opendrive_spiral.h
@@ -0,0 +1,26 @@
+#ifndef _OPENDRIVE_SPIRAL_H
+#define _OPENDRIVE_SPIRAL_H
+
+#include "opendrive_geometry.h"
+
+class COpendriveSpiral : public COpendriveGeometry
+{
+  private:
+    double start_curvature;
+    double end_curvature;
+  protected:
+    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local);
+    virtual void print(std::ostream &out);
+    virtual void load_params(const planView::geometry_type &geometry_info);
+  public:
+    COpendriveSpiral();
+    COpendriveSpiral(double min_s, double max_s, double x, double y, double heading,double start_curv,double end_curv);
+    COpendriveSpiral(const COpendriveSpiral &object);
+    virtual COpendriveGeometry *clone(void);
+    double get_start_curvature(void);
+    double get_end_curvature(void);
+    void operator=(const COpendriveSpiral &object);
+    ~COpendriveSpiral();
+};
+
+#endif
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index bd96a3d..c6eb6ac 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -1,18 +1,29 @@
 # driver source files
-SET(sources gradient.cpp g2_spline.cpp dijkstra.cpp)
+SET(sources gradient.cpp g2_spline.cpp dijkstra.cpp opendrive_geometry.cpp opendrive_common.cpp opendrive_line.cpp opendrive_spiral.cpp opendrive_arc.cpp opendrive_param_poly3.cpp opendrive_signal.cpp opendrive_object.cpp opendrive_road.cpp opendrive_road_segment.cpp opendrive_lane.cpp opendrive_road_node.cpp opendrive_link.cpp)
 
 # application header files
-SET(headers ../include/gradient.h ../include/g2_spline.h ../include/dijkstra.h)
+SET(headers ../include/gradient.h ../include/g2_spline.h ../include/dijkstra.h ../include/opendrive_common.h ../include/opendrive_geometry.h ../include/opendrive_line.h ../include/opendrive_spiral.h ../include/opendrive_arc.h ../include/opendrive_param_poly3.h ../include/opendrive_signal.h ../include/opendrive_object.h ../include/opendrive_road.h ../include/opendrive_road_segment.h ../include/opendrive_lane.h ../include/opendrive_road_node.h ../include/opendrive_link.h)
 
 # locate the necessary dependencies
 find_package(Eigen3 REQUIRED)
+find_package(iriutils REQUIRED)
+
+ADD_SUBDIRECTORY(xml)
 
 # add the necessary include directories
 INCLUDE_DIRECTORIES(../include)
 INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIR})
+INCLUDE_DIRECTORIES(${iriutils_INCLUDE_DIR})
 
 # create the shared library
-ADD_LIBRARY(${PROJECT_NAME} SHARED ${sources})
+ADD_LIBRARY(${PROJECT_NAME} SHARED ${sources} ${XSD_SOURCES})
+
+TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${XSD_LIBRARY})
+TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${iriutils_LIBRARY})
+
+ADD_DEPENDENCIES(${PROJECT_NAME} xsd_files_gen)
+
+SET_SOURCE_FILES_PROPERTIES(${XSD_SOURCES} PROPERTIES GENERATED 1)
 
 # link necessary libraries
 INSTALL(TARGETS ${PROJECT_NAME}
diff --git a/src/examples/CMakeLists.txt b/src/examples/CMakeLists.txt
index a5d59c3..34527a7 100644
--- a/src/examples/CMakeLists.txt
+++ b/src/examples/CMakeLists.txt
@@ -2,3 +2,8 @@
 ADD_EXECUTABLE(dijkstra_test dijkstra_test.cpp)
 # link necessary libraries
 TARGET_LINK_LIBRARIES(dijkstra_test ${PROJECT_NAME})
+
+# create an example application
+ADD_EXECUTABLE(opendrive_test opendrive_test.cpp)
+# link necessary libraries
+TARGET_LINK_LIBRARIES(opendrive_test ${PROJECT_NAME})
diff --git a/src/examples/opendrive_test.cpp b/src/examples/opendrive_test.cpp
new file mode 100644
index 0000000..8764f9b
--- /dev/null
+++ b/src/examples/opendrive_test.cpp
@@ -0,0 +1,25 @@
+#include "opendrive_road.h"
+#include "exceptions.h"
+#include <iostream>
+#include <vector>
+#include <limits>
+
+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";
+  
+  try
+  {
+    road.set_resolution(0.01);
+    road.set_scale_factor(10.0);
+    road.set_min_road_length(0.01);
+    road.load(xml_file);
+    std::cout << road << std::endl;
+  }
+  catch (CException &e)
+  {
+    std::cout << "[Exception caught] : " << e.what() << std::endl;
+  }
+  return 0;
+}
diff --git a/src/opendrive_arc.cpp b/src/opendrive_arc.cpp
new file mode 100644
index 0000000..63c4645
--- /dev/null
+++ b/src/opendrive_arc.cpp
@@ -0,0 +1,65 @@
+#include "opendrive_arc.h"
+#include <cmath>
+
+COpendriveArc::COpendriveArc()
+{
+  this->curvature=0.0;
+}
+
+COpendriveArc::COpendriveArc(double min_s, double max_s, double x, double y, double heading, double curvature) : COpendriveGeometry(min_s,max_s,x,y,heading)
+{
+  this->curvature=curvature;
+}
+
+COpendriveArc::COpendriveArc(const COpendriveArc &object) : COpendriveGeometry(object)
+{
+  this->curvature=object.curvature;
+}
+
+bool COpendriveArc::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+  double alpha;
+  bool pos_arc;
+
+  alpha = std::fabs((track.s-this->min_s)*this->curvature);
+  pos_arc = (this->curvature < 0.0 ? false : true);
+  local.u = std::sin(alpha)/this->curvature - track.t*std::sin(alpha)*(pos_arc ? 1 : -1);
+  local.v = (1 - std::cos(alpha))*(pos_arc ? 1 : -1)/this->curvature + track.t*std::cos(alpha);
+  local.heading = normalize_angle(track.heading + alpha*(pos_arc ? 1 : -1));
+
+  return true;
+}
+
+void COpendriveArc::print(std::ostream &out)
+{
+  out << "  curvature = " << this->curvature << std::endl;
+}
+
+void COpendriveArc::load_params(const planView::geometry_type &geometry_info)
+{
+  this->curvature = (geometry_info.arc().get().curvature().present() ? geometry_info.arc().get().curvature().get() : 0.0);
+}
+
+COpendriveGeometry *COpendriveArc::clone(void)
+{
+  COpendriveArc *new_arc=new COpendriveArc(*this);
+
+  return new_arc;
+}
+
+double COpendriveArc::get_curvature(void)
+{
+  return this->curvature;
+}
+
+void COpendriveArc::operator=(const COpendriveArc &object)
+{
+  COpendriveGeometry::operator=(object);
+  this->curvature=object.curvature;
+}
+
+COpendriveArc::~COpendriveArc()
+{
+  this->curvature=0.0;
+}
+
diff --git a/src/opendrive_common.cpp b/src/opendrive_common.cpp
new file mode 100644
index 0000000..c81c8de
--- /dev/null
+++ b/src/opendrive_common.cpp
@@ -0,0 +1,29 @@
+#include "opendrive_common.h"
+#include <cmath>
+
+double normalize_angle(double angle)
+{
+  double norm_angle;
+
+  if(angle>=2*3.14159)
+    norm_angle=angle-2*3.14159;
+  else if(angle<0.0)
+    norm_angle=angle+2*3.14159;
+  else
+    norm_angle=angle;
+
+  return norm_angle;
+}
+
+double diff_angle(double angle1,double angle2)
+{
+  double diff1,diff2;
+
+  diff1=std::fabs(angle1-angle2);
+  if(angle1<angle2)
+    diff2=std::fabs(angle1+2*3.14159-angle2);
+  else
+    diff2=std::fabs(angle1-angle2-2*3.14159);
+
+  return std::fmin(diff1,diff2);
+}
diff --git a/src/opendrive_geometry.cpp b/src/opendrive_geometry.cpp
new file mode 100644
index 0000000..b76bf69
--- /dev/null
+++ b/src/opendrive_geometry.cpp
@@ -0,0 +1,103 @@
+#include "opendrive_geometry.h"
+#include <cmath>
+
+COpendriveGeometry::COpendriveGeometry()
+{
+  this->min_s = 0.0;
+  this->max_s = 0.0;
+  this->pose.x = 0.0;
+  this->pose.y = 0.0;
+  this->pose.heading = 0.0;
+}
+
+COpendriveGeometry::COpendriveGeometry(double min_s, double max_s, double x, double y, double heading)
+{
+  this->min_s = min_s;
+  this->max_s = max_s;
+  this->pose.x = x;
+  this->pose.y = y;
+  this->pose.heading = heading;
+}
+
+COpendriveGeometry::COpendriveGeometry(const COpendriveGeometry &object)
+{
+  this->min_s = object.min_s;
+  this->max_s = object.max_s;
+  this->pose.x = object.pose.x;
+  this->pose.y = object.pose.y;
+  this->pose.heading = object.pose.heading;
+}
+
+void COpendriveGeometry::print(std::ostream& out)
+{
+  out << "  Geometry from " << this->min_s << " to " << this->max_s << std::endl;
+  out << "    pose: x = " << this->pose.x << ", y = " << this->pose.y << ", heading = " << this->pose.heading << std::endl;
+}
+
+void COpendriveGeometry::load(const planView::geometry_type &geometry_info)
+{
+  this->min_s = (geometry_info.s().present() ? geometry_info.s().get() : 0.0);
+  this->max_s = min_s + (geometry_info.length().present() ? geometry_info.length().get() : 0.0);
+  this->pose.x = (geometry_info.x().present() ? geometry_info.x().get() : 0.0);
+  this->pose.y = (geometry_info.y().present() ? geometry_info.y().get() : 0.0);
+  this->pose.heading = (geometry_info.hdg().present() ? geometry_info.hdg().get() : 0.0);
+  this->load_params(geometry_info);
+}
+
+bool COpendriveGeometry::get_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+  return this->transform_local_pose(track,local);
+}
+
+bool COpendriveGeometry::get_world_pose(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world)
+{
+  TOpendriveLocalPoint local;
+
+  if(this->transform_local_pose(track,local))
+  {
+    world.heading=normalize_angle(this->pose.heading+local.heading);
+    world.x=local.u*std::cos(this->pose.heading)-local.v*std::sin(this->pose.heading)+this->pose.x;
+    world.y=local.u*std::sin(this->pose.heading)+local.v*std::cos(this->pose.heading)+this->pose.y;
+    return true;
+  }
+  else
+    return false;
+}
+
+bool COpendriveGeometry::in_range(double s)
+{
+  if((s<this->max_s) && (s>=this->min_s))
+    return true;
+  else 
+    return false;
+}
+
+double COpendriveGeometry::get_length(void)
+{
+  return this->max_s-this->min_s;
+}
+
+void COpendriveGeometry::operator=(const COpendriveGeometry &object)
+{
+  this->min_s = object.min_s;
+  this->max_s = object.max_s;
+  this->pose.x = object.pose.x;
+  this->pose.y = object.pose.y;
+  this->pose.heading = object.pose.heading;
+}
+
+std::ostream& operator<<(std::ostream& out, COpendriveGeometry &geom)
+{
+  geom.print(out);
+  return out;
+}
+
+COpendriveGeometry::~COpendriveGeometry()
+{
+  this->min_s = 0.0;
+  this->max_s = 0.0;
+  this->pose.x = 0.0;
+  this->pose.y = 0.0;
+  this->pose.heading = 0.0;
+}
+
diff --git a/src/opendrive_lane.cpp b/src/opendrive_lane.cpp
new file mode 100644
index 0000000..384fbe4
--- /dev/null
+++ b/src/opendrive_lane.cpp
@@ -0,0 +1,138 @@
+#include "opendrive_lane.h"
+
+COpendriveLane::COpendriveLane()
+{
+  this->nodes.clear();
+  this->segment=NULL;
+  this->scale_factor=DEFAULT_SCALE_FACTOR;
+  this->width=0.0;
+  this->speed=0.0;
+  this->offset=0.0;
+}
+
+COpendriveLane::COpendriveLane(const COpendriveLane &object)
+{
+  COpendriveRoadNode *node;
+
+  this->nodes.clear();
+  for(unsigned int i=0;i<object.nodes.size();i++)
+  {
+    node=new COpendriveRoadNode(*object.nodes[i]);
+    this->nodes.push_back(node);
+  }
+  this->width=object.width;
+  this->speed=object.speed;
+  this->offset=object.offset;
+}
+
+void COpendriveLane::add_node(COpendriveRoadNode *node)
+{
+
+}
+
+void COpendriveLane::set_resolution(double res)
+{ 
+  for(unsigned int i=0;i<this->nodes.size();i++)
+    this->nodes[i]->set_resolution(res);
+}
+
+void COpendriveLane::set_scale_factor(double scale)
+{ 
+  this->scale_factor=scale;
+
+  for(unsigned int i=0;i<this->nodes.size();i++)
+    this->nodes[i]->set_scale_factor(scale);
+}
+
+void COpendriveLane::set_offset(double offset)
+{
+  this->offset=offset;
+}
+
+void COpendriveLane::update_references(std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> refs)
+{
+  this->segment=refs[this->segment];
+}
+
+void COpendriveLane::load(const right::lane_type &lane_info,COpendriveRoadSegment *segment)
+{
+  std::stringstream error;
+
+  for(unsigned int i=0;i<this->nodes.size();i++)
+  {
+    delete this->nodes[i];
+    this->nodes[i]=NULL;
+  }
+  this->nodes.clear();
+  // import lane width
+  if(lane_info.width().size()<1)
+  {
+    error << "No width record present for lane " << lane_info.id().get() << " for road " << road_name;
+    throw CException(_HERE_,error.str());
+  }
+  else if(lane_info.width().size()>1)
+  {
+    error << "More than one width record present for lane " << lane_info.id().get() << " for road " << road_name;
+    throw CException(_HERE_,error.str());
+  }
+  this->width=lane_info.width().begin()->a().get()/this->scale_factor;
+  // import lane speed
+  if(lane_info.speed().size()<1)
+  {
+    error << "No speed record present for lane " << lane_info.id().get() << " for road " << road_name;
+    throw CException(_HERE_,error.str());
+  }
+  else if(lane_info.speed().size()>1)
+  {
+    error << "More than one speed record present for lane " << lane_info.id().get() << " for road " << road_name;
+    throw CException(_HERE_,error.str());
+  }
+  this->speed=lane_info.speed().begin()->max().get();
+
+  this->segment=segment;
+}
+
+unsigned int COpendriveLane::get_num_nodes(void)
+{
+  return this->nodes.size();
+}
+
+const COpendriveRoadNode &COpendriveLane::get_node(unsigned int index)
+{
+
+}
+
+const COpendriveRoadSegment &COpendriveLane::get_segment(void)
+{
+
+}
+
+double COpendriveLane::get_width(void)
+{
+  return this->width;
+}
+
+double COpendriveLane::get_speed(void)
+{
+  return this->speed;
+}
+
+double COpendriveLane::get_offset(void)
+{
+  return this->offset;
+}
+
+void COpendriveLane::operator=(const COpendriveLane &object)
+{
+
+}
+
+friend std::ostream& operator<<(std::ostream& out, COpendriveLane &lane)
+{
+
+}
+
+COpendriveLane::~COpendriveLane()
+{
+
+}
diff --git a/src/opendrive_line.cpp b/src/opendrive_line.cpp
new file mode 100644
index 0000000..38f4f35
--- /dev/null
+++ b/src/opendrive_line.cpp
@@ -0,0 +1,53 @@
+#include "opendrive_line.h"
+
+COpendriveLine::COpendriveLine()
+{
+
+}
+
+COpendriveLine::COpendriveLine(double min_s, double max_s, double x, double y, double heading) : COpendriveGeometry(min_s,max_s,x,y,heading)
+{
+
+}
+
+COpendriveLine::COpendriveLine(const COpendriveGeometry &object) : COpendriveGeometry(object)
+{
+
+}
+
+bool COpendriveLine::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+  local.u=track.s-this->min_s;
+  local.v=track.t;
+  local.heading=track.heading;
+
+  return true;
+}
+
+void COpendriveLine::print(std::ostream &out)
+{
+  COpendriveGeometry::print(out);
+}
+
+void COpendriveLine::load_params(const planView::geometry_type &geometry_info)
+{
+
+}
+
+COpendriveGeometry *COpendriveLine::clone(void)
+{
+  COpendriveLine *new_line=new COpendriveLine(*this);
+
+  return new_line;
+}
+
+void COpendriveLine::operator=(const COpendriveLine &object)
+{
+  COpendriveGeometry::operator=(object);
+}
+
+COpendriveLine::~COpendriveLine()
+{
+
+}
+
diff --git a/src/opendrive_link.cpp b/src/opendrive_link.cpp
new file mode 100644
index 0000000..8f3131c
--- /dev/null
+++ b/src/opendrive_link.cpp
@@ -0,0 +1,102 @@
+#include "opendrive_link.h"
+
+COpendriveLink::COpendriveLink()
+{
+
+}
+
+COpendriveLink::COpendriveLink(const COpendriveLink &object)
+{
+
+}
+
+void COpendriveLink::set_prev(COpendriveRoadNode *node)
+{
+
+}
+
+void COpendriveLink::set_next(COpendriveRoadNode *node)
+{
+
+}
+
+void COpendriveLink::set_road_mark(opendrive_mark_t mark)
+{
+
+}
+
+void COpendriveLink::set_resolution(double res)
+{
+
+}
+
+void COpendriveLink::set_scale_factor(double scale)
+{
+
+}
+
+const COpendriveRoadNode &COpendriveLink::get_prev(void)
+{
+
+}
+
+const COpendriveRoadNode &COpendriveLink::get_next(void)
+{
+
+}
+
+opendrive_mark_t COpendriveLink::get_road_mark(void)
+{
+
+}
+
+double COpendriveLink::get_resolution(void)
+{
+
+}
+
+double COpendriveLink::get_scale_factor(void)
+{
+
+}
+
+double COpendriveLink::find_closest_world_point(TOpendriveWorldPoint &world,TPoint &point)
+{
+
+}
+
+double COpendriveLink::find_closest_local_point(TOpendriveLocalPoint &local,TPoint &point)
+{
+
+}
+
+double COpendriveLink::get_track_point_world(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world)
+{
+
+}
+
+double COpendriveLink::get_track_point_local(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+
+}
+
+double COpendriveLink::get_length(void)
+{
+
+}
+
+void COpendriveLink::operator=(const COpendriveLink &object)
+{
+
+}
+
+friend std::ostream& operator<<(std::ostream& out, COpendriveLink &link)
+{
+
+}
+
+COpendriveLink::~COpendriveLink()
+{
+
+}
+
diff --git a/src/opendrive_object.cpp b/src/opendrive_object.cpp
new file mode 100644
index 0000000..b6db96c
--- /dev/null
+++ b/src/opendrive_object.cpp
@@ -0,0 +1,231 @@
+#include "opendrive_object.h"
+#include <cmath>
+
+COpendriveObject::COpendriveObject()
+{
+  this->pose.s=0.0;
+  this->pose.t=0.0;
+  this->pose.heading=0.0;
+  this->type="";
+  this->name="";
+  this->object_type=OD_NONE;
+}
+
+COpendriveObject::COpendriveObject(const COpendriveObject& object)
+{
+  this->pose.s=object.pose.s;
+  this->pose.s=object.pose.t;
+  this->pose.heading=object.pose.heading;
+  this->type=object.type;
+  this->name=object.name;
+  this->object_type=object.object_type;
+  switch(this->object_type)
+  {
+    case OD_BOX: 
+      this->object.box.length=object.object.box.length;
+      this->object.box.width=object.object.box.width;
+      this->object.box.height=object.object.box.height;
+      break;
+    case OD_CYLINDER:
+      this->object.cylinder.radius=object.object.cylinder.radius;
+      this->object.cylinder.height=object.object.cylinder.height;
+      break;
+    case OD_POLYGON:
+      for(unsigned int i=0;i<object.object.polygon.num_vertices;i++)
+      {
+        this->object.polygon.vertices[i]=object.object.polygon.vertices[i];
+        this->object.polygon.height[i]=object.object.polygon.height[i];
+      }
+      this->object.polygon.num_vertices=object.object.polygon.num_vertices;
+      break;
+    case OD_NONE:
+      break;
+  }
+}
+
+void COpendriveObject::load(std::unique_ptr<objects::object_type> &object_info)
+{
+  double u,v;
+  unsigned int i;
+  std::stringstream ss(object_info->id().get());
+  outline::cornerRoad_iterator corner_road_it;
+  outline::cornerLocal_iterator corner_local_it;
+
+  ss >> this->id;
+  this->pose.s = (object_info->s().present() ? object_info->s().get() : 0.0);
+  this->pose.t = (object_info->t().present() ? object_info->t().get() : 0.0);
+  this->pose.heading = (object_info->hdg().present() ? object_info->hdg().get() : 0.0);
+  this->type = (object_info->type().present() ? object_info->type().get() : "");
+  this->name = (object_info->name().present() ? object_info->name().get() : "");
+  if(object_info->length().present() && object_info->width().present() && object_info->height().present())
+  {
+    this->object_type=OD_BOX;
+    this->object.box.length=object_info->length().get();
+    this->object.box.width=object_info->width().get();
+    this->object.box.height=object_info->height().get();
+  }
+  else if(object_info->height().present() && object_info->radius().present())
+  {
+    this->object_type=OD_CYLINDER;
+    this->object.cylinder.radius=object_info->radius().get();
+    this->object.cylinder.height=object_info->height().get();
+  }
+  else if(object_info->outline().present())
+  {
+    this->object_type=OD_POLYGON;
+    this->object.polygon.num_vertices=0;
+    // absolute track coordinates
+    if(object_info->outline().get().cornerRoad().size()>0)// absolute track coordinates
+    {
+      for(i=0,corner_road_it=object_info->outline().get().cornerRoad().begin();i<OD_MAX_VERTICES && corner_road_it != object_info->outline().get().cornerRoad().end(); ++corner_road_it,++i)
+      {
+        this->object.polygon.vertices[i].s=(corner_road_it->s().present() ? corner_road_it->s().get() : 0.0);
+        this->object.polygon.vertices[i].t=(corner_road_it->t().present() ? corner_road_it->t().get() : 0.0);
+        this->object.polygon.height[i]=(corner_road_it->height().present() ? corner_road_it->height().get() : 0.0);
+        this->object.polygon.num_vertices++;
+      }
+    }
+    else if(object_info->outline().get().cornerLocal().size()>0)// local coordinates with respect to the object anchor point
+    {
+      for(i=0,corner_local_it=object_info->outline().get().cornerLocal().begin();i<OD_MAX_VERTICES && corner_local_it != object_info->outline().get().cornerLocal().end(); ++corner_local_it,++i)
+      {
+        u=(corner_local_it->u().present() ? corner_local_it->u().get() : 0.0);
+        v=(corner_local_it->v().present() ? corner_local_it->v().get() : 0.0);
+        this->object.polygon.vertices[i].s=this->pose.s + u*cos(this->pose.heading) - v*sin(this->pose.heading);
+        this->object.polygon.vertices[i].t=this->pose.t + u*sin(this->pose.heading) + v*cos(this->pose.heading);
+        this->object.polygon.height[i]=(corner_local_it->height().present() ? corner_local_it->height().get() : 0.0);
+        this->object.polygon.num_vertices++;
+      }
+    }
+  }
+  else
+    this->object_type=OD_NONE;
+}
+
+TOpendriveTrackPoint COpendriveObject::get_pose(void)
+{
+  return this->pose;
+}
+
+std::string COpendriveObject::get_type(void)
+{
+  return this->type;
+}
+
+std::string COpendriveObject::get_name(void)
+{
+  return this->name;
+}
+
+bool COpendriveObject::is_box(void)
+{
+  if(this->object_type==OD_BOX)
+    return true;
+  else
+    return false;
+}
+
+bool COpendriveObject::is_cylinder(void)
+{
+  if(this->object_type==OD_CYLINDER)
+    return true;
+  else
+    return false;
+}
+
+bool COpendriveObject::is_polygon(void)
+{
+  if(this->object_type==OD_POLYGON)
+    return true;
+  else
+    return false;
+}
+
+TOpendriveBox COpendriveObject::get_box_data(void)
+{
+  return this->object.box;
+}
+
+TOpendriveCylinder COpendriveObject::get_cylinder_data(void)
+{
+  return this->object.cylinder;
+}
+
+TOpendrivePolygon COpendriveObject::get_polygon_data(void)
+{
+  return this->object.polygon;
+}
+
+void COpendriveObject::operator=(const COpendriveObject &object)
+{
+  this->pose.s=object.pose.s;
+  this->pose.s=object.pose.t;
+  this->pose.heading=object.pose.heading;
+  this->type=object.type;
+  this->name=object.name;
+  this->object_type=object.object_type;
+  switch(this->object_type)
+  {
+    case OD_BOX:
+      this->object.box.length=object.object.box.length;
+      this->object.box.width=object.object.box.width;
+      this->object.box.height=object.object.box.height;
+      break;
+    case OD_CYLINDER:
+      this->object.cylinder.radius=object.object.cylinder.radius;
+      this->object.cylinder.height=object.object.cylinder.height;
+      break;
+    case OD_POLYGON:
+      for(unsigned int i=0;i<object.object.polygon.num_vertices;i++)
+      {
+        this->object.polygon.vertices[i]=object.object.polygon.vertices[i];
+        this->object.polygon.height[i]=object.object.polygon.height[i];
+      }
+      this->object.polygon.num_vertices=object.object.polygon.num_vertices;
+      break;
+    case OD_NONE:
+      break;
+  }
+}
+
+std::ostream& operator<<(std::ostream& out, COpendriveObject &object)
+{
+  out << "  Object id = " << object.id << std::endl;
+  out << "    type = " << object.type << std::endl;
+  out << "    name = " << object.name << std::endl;
+  out << "    pose: s = " << object.pose.s  << ", t = " << object.pose.t << ", heading = " << object.pose.heading << std::endl;
+  switch(object.object_type)
+  {
+    case OD_BOX:
+      out << "    box:" << std::endl;
+      out << "      length = " << object.object.box.length << std::endl;
+      out << "      width = " << object.object.box.width << std::endl;
+      out << "      height = " << object.object.box.height << std::endl;
+      break;
+    case OD_CYLINDER:
+      out << "    cylinder:" << std::endl;
+      out << "      radius = " << object.object.cylinder.radius << std::endl;
+      out << "      height = " << object.object.cylinder.height << std::endl;
+      break;
+    case OD_POLYGON:
+      out << "    polygon: " << object.object.polygon.num_vertices << " vertices" << std::endl;
+      for (unsigned int i = 0; i < object.object.polygon.num_vertices; i++)
+        out << "      vertex " << i << ": s = " << object.object.polygon.vertices[i].s  << ", t = " << object.object.polygon.vertices[i].t << ", height: " << object.object.polygon.height[i] << std::endl;
+      break;
+    case OD_NONE:
+      break;
+  }
+
+  return out;
+}
+
+COpendriveObject::~COpendriveObject()
+{
+  this->pose.s=0.0;
+  this->pose.t=0.0;
+  this->pose.heading=0.0;
+  this->type="";
+  this->name="";
+  this->object_type=OD_NONE;
+}
+
diff --git a/src/opendrive_param_poly3.cpp b/src/opendrive_param_poly3.cpp
new file mode 100644
index 0000000..8be71e6
--- /dev/null
+++ b/src/opendrive_param_poly3.cpp
@@ -0,0 +1,131 @@
+#include "opendrive_param_poly3.h"
+#include <cmath>
+
+COpendriveParamPoly3::COpendriveParamPoly3()
+{
+  this->u.a=0.0;  
+  this->u.b=0.0;  
+  this->u.c=0.0;  
+  this->u.c=0.0;  
+  this->v.a=0.0;  
+  this->v.b=0.0;  
+  this->v.c=0.0;  
+  this->v.c=0.0;
+  this->normalized=true;
+}
+
+COpendriveParamPoly3::COpendriveParamPoly3(double min_s, double max_s, double x, double y, double heading,TOpendrivePoly3Params &u,TOpendrivePoly3Params &v,bool normalized) : COpendriveGeometry(min_s,max_s,x,y,heading)
+{
+  this->u.a=u.a;
+  this->u.b=u.b;
+  this->u.c=u.c;
+  this->u.d=u.d;
+  this->v.a=v.a;
+  this->v.b=v.b;
+  this->v.c=v.c;
+  this->v.d=v.d;
+  this->normalized=normalized;
+}
+
+COpendriveParamPoly3::COpendriveParamPoly3(const COpendriveParamPoly3 &object) : COpendriveGeometry(object)
+{
+  this->u.a=object.u.a;
+  this->u.b=object.u.b;
+  this->u.c=object.u.c;
+  this->u.d=object.u.d;
+  this->v.a=object.v.a;
+  this->v.b=object.v.b;
+  this->v.c=object.v.c;
+  this->v.d=object.v.d;
+  this->normalized=object.normalized;
+}
+
+bool COpendriveParamPoly3::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+  double p = (this->normalized ? (track.s - this->min_s)/(this->max_s - this->min_s): (track.s - this->min_s));
+  double p2 = p*p;
+  double p3 = p2*p;
+  double du = this->u.b + 2*this->u.c*p + 3*this->u.d*p2;
+  double dv = this->v.b + 2*this->v.c*p + 3*this->v.d*p2;
+  double alpha = std::atan2(dv, du);
+  local.u = this->u.a + this->u.b*p + this->u.c*p2 + this->u.d*p3 - track.t*std::sin(alpha);
+  local.v = this->v.a + this->v.b*p + this->v.c*p2 + this->v.d*p3 + track.t*std::cos(alpha);
+  local.heading = normalize_angle(track.heading + alpha);
+
+  return true;
+}
+
+void COpendriveParamPoly3::print(std::ostream &out)
+{
+  std::cout << "  U params: a = " << this->u.a << ", b = " << this->u.b  << ", c = " << this->u.c  << ", d = " << this->u.d << std::endl;
+  std::cout << "  V params: a = " << this->v.a << ", b = " << this->v.b  << ", c = " << this->v.c  << ", d = " << this->v.d << std::endl;
+  if(this->normalized)
+    std::cout << "  Normalized" << std::endl;
+  else
+    std::cout << "  Not normalized" << std::endl;
+}
+
+void COpendriveParamPoly3::load_params(const planView::geometry_type &geometry_info)
+{
+  this->u.a = (geometry_info.paramPoly3().get().aU().present() ? geometry_info.paramPoly3().get().aU().get() : 0.0);
+  this->u.b = (geometry_info.paramPoly3().get().bU().present() ? geometry_info.paramPoly3().get().bU().get() : 0.0);
+  this->u.c = (geometry_info.paramPoly3().get().cU().present() ? geometry_info.paramPoly3().get().cU().get() : 0.0);
+  this->u.d = (geometry_info.paramPoly3().get().dU().present() ? geometry_info.paramPoly3().get().dU().get() : 0.0);
+  this->v.a = (geometry_info.paramPoly3().get().aV().present() ? geometry_info.paramPoly3().get().aV().get() : 0.0);
+  this->v.b = (geometry_info.paramPoly3().get().bV().present() ? geometry_info.paramPoly3().get().bV().get() : 0.0);
+  this->v.c = (geometry_info.paramPoly3().get().cV().present() ? geometry_info.paramPoly3().get().cV().get() : 0.0);
+  this->v.d = (geometry_info.paramPoly3().get().dV().present() ? geometry_info.paramPoly3().get().dV().get() : 0.0);
+  this->normalized = true;
+  if (geometry_info.paramPoly3().get().pRange().present() && geometry_info.paramPoly3().get().pRange().get() == pRange::arcLength)
+    this->normalized = false;
+}
+
+COpendriveGeometry *COpendriveParamPoly3::clone(void)
+{
+  COpendriveParamPoly3 *new_poly=new COpendriveParamPoly3(*this);
+
+  return new_poly;
+}
+
+TOpendrivePoly3Params COpendriveParamPoly3::get_u_params(void)
+{
+  return this->u;
+}
+
+TOpendrivePoly3Params COpendriveParamPoly3::get_v_params(void)
+{
+  return this->v;
+}
+
+bool COpendriveParamPoly3::is_normalized(void)
+{
+  return this->normalized;
+}
+
+void COpendriveParamPoly3::operator=(const COpendriveParamPoly3 &object)
+{
+  COpendriveGeometry::operator=(object);
+  this->u.a=object.u.a;
+  this->u.b=object.u.b;
+  this->u.c=object.u.c;
+  this->u.d=object.u.d;
+  this->v.a=object.v.a;
+  this->v.b=object.v.b;
+  this->v.c=object.v.c;
+  this->v.d=object.v.d;
+  this->normalized=object.normalized;
+}
+
+COpendriveParamPoly3::~COpendriveParamPoly3()
+{
+  this->u.a=0.0;  
+  this->u.b=0.0;  
+  this->u.c=0.0;  
+  this->u.c=0.0;  
+  this->v.a=0.0;  
+  this->v.b=0.0;  
+  this->v.c=0.0;  
+  this->v.c=0.0;  
+  this->normalized=true;
+}
+
diff --git a/src/opendrive_road.cpp b/src/opendrive_road.cpp
new file mode 100644
index 0000000..dea20a4
--- /dev/null
+++ b/src/opendrive_road.cpp
@@ -0,0 +1,162 @@
+#include "opendrive_road.h"
+#include <sys/types.h>
+#include <sys/stat.h>
+#include "exceptions.h"
+
+COpendriveRoad::COpendriveRoad()
+{
+  this->resolution=DEFAULT_RESOLUTION;
+  this->scale_factor=DEFAULT_SCALE_FACTOR;
+  this->min_road_length=DEFAULT_MIN_ROAD_LENGTH;
+  this->segments.clear();
+}
+
+COpendriveRoad::COpendriveRoad(const COpendriveRoad& object)
+{
+  COpendriveRoadSegment *segment;
+  std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> new_references;
+
+  this->resolution=object.resolution;
+  this->scale_factor=object.scale_factor;
+  this->min_road_length=object.min_road_length;
+  this->segments.clear();
+  for(unsigned int i=0;i<object.segments.size();i++)
+  {
+    segment=new COpendriveSegment(*object.segment[i]);
+    this->segments.push_back(segment);
+    new_references[object.segment[i]]=segment;
+  }
+  for(unsigned int i=0;i<this->segments.size();i++)
+    this->segments[i]->update_referecnes(new_references);
+}
+
+void COpendriveRoad::load(const std::string &filename)
+{
+  struct stat buffer;
+  COpendriveRoadSegment *segment;
+
+  if(stat(filename.c_str(),&buffer)==0)
+  {
+    // delete any previous data
+    for(unsigned int i=0;i<this->segments.size();i++)
+      delete this->segments[i];
+    this->segments.clear();
+    // 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)
+      {
+        segment=new COpendriveRoadSegment();
+        segment->load(*road_it);
+        this->segments.push_back(segment);
+      }
+    }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);
+}
+
+double COpendriveRoad::get_resolution(void)
+{
+  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);
+}
+
+double COpendriveRoad::get_scale_factor(void)
+{
+  return this->scale_factor;
+}
+
+void COpendriveRoad::set_min_road_length(double length)
+{
+  this->min_road_length=length;
+}
+
+double COpendriveRoad::get_min_road_length(void)
+{
+  return this->min_road_length;
+}
+
+unsigned int COpendriveRoad::get_num_segments(void)
+{
+  return this->segments.size();
+}
+
+const COpendriveRoadNode& COpendriveRoad::get_segment(unsigned int index)
+{
+  if(index>=0 && index<this->segments.size())
+    return *this->segments[index];
+  else
+    throw CException(_HERE_,"Invalid segment index");
+}
+
+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");
+}
+
+void COpendriveRoad::operator=(const COpendriveRoad& object)
+{
+ COpendriveRoadSegment *segment;
+  std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> new_references;
+
+  this->resolution=object.resolution;
+  this->scale_factor=object.scale_factor;
+  this->min_road_length=object.min_road_length;
+  this->segments.clear();
+  for(unsigned int i=0;i<object.segments.size();i++)
+  {
+    segment=new COpendriveSegment(*object.segment[i]);
+    this->segments.push_back(segment);
+    new_references[object.segment[i]]=segment;
+  }
+  for(unsigned int i=0;i<this->segments.size();i++)
+    this->segments[i]->update_referecnes(new_references);
+}
+
+std::ostream& operator<<(std::ostream& out, COpendriveRoad &road)
+{
+  out << "Resolution: " << road>resolution << std::endl;
+  out << "Scale factor: " << road->scale_factor << std::endl;
+  out << "Minimum road lenght: " << road->min_road_length << std::endl;
+  for(unsigned int i=0;i<road->segments;i++)
+    std::cout << road->segments[i] << std::endl;
+
+  return out;
+}
+
+COpendriveRoad::~COpendriveRoad()
+{
+  for(unsigned int i=0;i<this->segments.size();i++)
+    delete this->segments[i];
+  this->nodes.segments();
+  this->resolution=DEFAULT_RESOLUTION;
+  this->scale_factor=DEFAULT_SCALE_FACTOR;
+  this->min_road_length=DEFAULT_MIN_ROAD_LENGTH;
+}
+
diff --git a/src/opendrive_road_node.cpp b/src/opendrive_road_node.cpp
new file mode 100644
index 0000000..65e1f8e
--- /dev/null
+++ b/src/opendrive_road_node.cpp
@@ -0,0 +1,186 @@
+#include "opendrive_road_node.h"
+#include "exceptions.h"
+
+COpendriveRoadNode::COpendriveRoadNode()
+{
+  this->resolution=DEFAULT_RESOLUTION;
+  this->scale_factor=DEFAULT_SCALE_FACTOR;
+  this->start_point.x=0.0;
+  this->start_point.y=0.0;
+  this->start_point.heading=0.0;
+  this->lane=NULL;
+  this->geometry=NULL;
+}
+
+COpendriveRoadNode::COpendriveRoadNode(const COpendriveRoadNode &object)
+{
+  COpendriveLink *new_link;
+
+  this->resolution=object.resolution;
+  this->scale_factor=object.scale_factor;
+  this->start_point.x=object.start_point.x;
+  this->start_point.y=object.start_point.y;
+  this->start_point.heading=object.start_point.heading;
+  this->lane=object.lane;
+  this->geometry=object.clone();
+  this->links.clear();
+  for(unsigned int i=0;i<object.links.size();i++)
+  {
+    new_link=new COpendriveLink(*object.link[i]);
+    this->links.puahs_back(new_link);
+  }
+}
+
+unsigned int COpendriveRoadNode::add_link(COpendriveRoadNode *parent)
+{
+
+}
+
+void COpendriveRoadNode::set_resolution(double res)
+{
+  this->resolution=res;
+}
+
+void COpendriveRoadNode::set_scale_factor(double scale)
+{
+  this->scale_factor=scale;
+}
+
+void COpendriveRoadNode::load(const planView::geometry_type &geom_info,COpendrive *lane)
+{
+  TOpendriveTrackPoint track_point;
+
+  if(this->geometry!=NULL)
+  {
+    delete this->geometry;
+    this->geometry=NULL;
+  }
+  // import geometry
+  if(geom_info.line().present())
+    this->geometry=new COpendriveLine();
+  else if(geom_info.spiral().present())
+    this->geometry=new COpendriveSpiral();
+  else if(geom_info.arc().present())
+    this->geometry=new COpendriveArc();
+  else if(geom_info.paramPoly3().present())
+    this->geometry=new COpendriveParamPoly3();
+  else
+    throw CException(_HERE_,"Unsupported or Missing geometry");
+  this->geometry->load(geom_info);
+  // import start position
+  track_point.s=0.0;
+  track_point.t=lane->get_offset()+lane->get_width()/2.0;
+  track_point.heading=0.0;
+  if(!this->geometry->get_world_pose(track_point,this->start_point))
+  {
+    delete this->geometry;
+    this->geometry=NULL;
+    throw CException(_HERE_,"Impossible to get world coordinates for this-");
+  }
+  this->start_point.x/=this->scale_factor;
+  this->start_point.y/=this->scale_factor;
+  for(unsigned int i=0;i<this->links.size();i++)
+  {
+    delete this->links[i];
+    this->links[i]=NULL;
+  }
+  this->links.clear();
+  this->lane=lane;
+}
+
+double COpendriveRoadNode::get_resolution(void)
+{
+  return this->resolution;
+}
+
+double COpendriveRoadNode::get_scale_factor(void)
+{
+  return this->scale_factor;
+}
+
+TOpendriveWorldPoint COpendriveRoadNode::get_start_pose(void)
+{
+  return this->start_point;
+}
+
+unsigned int COpendriveRoadNode::get_num_links(void)
+{
+  return this->links.size();
+}
+
+const COpendriveLink &COpendriveRoadNode::get_link(unsigned int index)
+{
+  if(index>=0 && index<this->links.size())
+    return *this->links[index];
+  else
+    throw CException(_HERE_,"Invalid link index");
+}
+
+const COpendriveLane &COpendriveRoadNode::get_lane(void)
+{
+  return *this->lane;
+}
+
+void COpendriveRoadNode::operator=(const COpendriveRoadNode &object)
+{
+  COpendriveLink *new_link;
+
+  this->resolution=object.resolution;
+  this->scale_factor=object.scale_factor;
+  this->start_point.x=object.start_point.x;
+  this->start_point.y=object.start_point.y;
+  this->start_point.heading=object.start_point.heading;
+  this->lane=object.lane;
+  this->geometry=object.clone();
+  for(unsigned int i=0;i<this->links.size();i++)
+  {
+    delete this->links[i];
+    this->links[i]=NULL;
+  }
+  this->links.clear();
+  for(unsigned int i=0;i<object.links.size();i++)
+  {
+    new_link=new COpendriveLink(*object.link[i]);
+    this->links.puahs_back(new_link);
+  }
+}
+
+std::ostream& operator<<(std::ostream& out, COpendriveRoadNode &node)
+{
+  return out;
+}
+
+COpendriveRoadNode::~COpendriveRoadNode()
+{
+  this->resolution=DEFAULT_RESOLUTION;
+  this->scale_factor=DEFAULT_SCALE_FACTOR;
+  this->start_point.x=0.0;
+  this->start_point.y=0.0;
+  this->start_point.heading=0.0;
+  this->index=-1;
+  this->lane=0;
+  this->station=-1;
+  this->name="";
+  this->parents.clear();
+  for(unsigned int i=0;i<this->children.size();i++)
+  {
+    delete this->children[i].spline;
+    this->children[i].spline=NULL;
+    delete this->children[i].geometry;
+    this->children[i].geometry=NULL;
+  }
+  this->children.clear();
+  for(unsigned int i=0;i<this->signals.size();i++)
+  {
+    delete this->signals[i];
+    this->signals[i]=NULL;
+  }
+  this->signals.clear();
+  for(unsigned int i=0;i<this->objects.size();i++)
+  {
+    delete this->objects[i];
+    this->objects[i]=NULL;
+  }
+  this->objects.clear();
+}
+
diff --git a/src/opendrive_road_segment.cpp b/src/opendrive_road_segment.cpp
new file mode 100644
index 0000000..7b08c5c
--- /dev/null
+++ b/src/opendrive_road_segment.cpp
@@ -0,0 +1,289 @@
+#include "opendrive_road_segment.h"
+
+COpendriveRoadSegment::COpendriveRoadSegment()
+{
+  this->name="";
+  this->id=-1;
+  this->lanes.clear();
+  this->num_left_lanes=0;
+  this->num_right_lanes=0;
+  this->signals.clear();
+  this->objects.clear();
+  this->next.clear();
+  this->prev.clear();
+}
+
+COpendriveRoadSegment::COpendriveRoadSegment(const COpendriveRoadSegment &object)
+{
+  COpendriveLane *lane;
+  COpendriveSignal *signal;
+  CopendriveObject *object;
+
+  this->name=object.name;
+  this->id=object.id;
+  this->lanes.clear();
+  for(unsigned int i=0;i<object.lanes.size();i++)
+  {
+    lane=new COpendriveLane(*object.lanes[i]);
+    this->lanes.push_back(lane);
+  }
+  this->signals.clear();
+  for(unsigned int i=0;i<object.signals.size();i++)
+  {
+    signal=new COpendriveSignal(*object.signals[i]);
+    this->signals.push_back(signal);
+  }
+  this->objects.clear();
+  for(unsigned int i=0;i<object.objects.size();i++)
+  {
+    object=new COpendriveObject(*object.objects[i]);
+    this->objects.push_back(object);
+  }
+  this->next.resize(object.next.size());
+  for(unsigned int i=0;i<object.next.size();i++)
+    this->next[i]=object.next[i];
+  this->next.resize(object.prev.size());
+  for(unsigned int i=0;i<object.prev.size();i++)
+    this->prev[i]=object.prev[i];
+}
+
+void COpendriveRoadSegment::set_resolution(double res)
+{
+  for(unsigned int i=-this->num_right_lanes;i<=this->num_left_lines && i!=0;i++)
+    this->lanes[i]->set_resolution(res);
+}
+
+void COpendriveRoadSegment::set_scale_factor(double scale)
+{
+  for(unsigned int i=-this->num_right_lanes;i<=this->num_left_lines && i!=0;i++)
+    this->lanes[i]->set_scale_factor(scale);
+}
+
+void COpendriveRoadSegment::update_references(std::map<COpendriveRoadSegment *,COpendriveRoadSegment *> refs)
+{
+  this->next=refs[this->next];
+  this->prev=refs[this->prev];
+
+  for(unsigned int i=0;i<this->lanes.size();i++)
+    this->lanes[i]->update_referecnes(refs);
+}
+
+void COpendriveRoadSegment::load_road(OpenDRIVE::road_type &road_info)
+{
+  lanes::laneSection_iterator lane_section;
+  right::lane_iterator r_lane_it;
+  left::lane_iterator l_lane_it;
+  planView::geometry_iterator geom_it;
+  COpendriveLane *new_lane;
+  COpendriveRoadNode *new_node;
+  double lane_offset;
+
+  this->name=road_info->name().get();
+  this->id=road_info->id().get();
+  // only one lane section is supported
+  if(road_info->lanes().laneSection().size()<1)
+    throw CException(_HERE_,"No lane sections defined for road "+road_info->id().get());
+  else if(road_info->lanes().laneSection().size()>1)
+    throw CException(_HERE_,"Road "+road_info->id().get()+" has more than one lane section");
+  else
+    lane_section=road_info->lanes().laneSection().begin();
+
+  // right lanes
+  if(lane_section->right().present())
+  {
+    for(r_lane_it=lane_section->right()->lane().begin();r_lane_it!=lane_section->right()->lane().end();r_lane_it++)
+    {
+      try{
+        new_lane=new COpendriveLane();
+        new_lane->load(*r_lane_it,this);
+        this->lanes[new_lane->get_id()]=new_lane;
+      }catch(CException &e){
+        std::cout << e.what() << std::endl;
+      }
+    }
+  }
+  // left lanes
+  if(lane_section->left().present())
+  {
+    for(l_lane_it=lane_section->left()->lane().begin();l_lane_it!=lane_section->left()->lane().end();l_lane_it++)
+    {
+      try{
+        new_lane=new COpendriveLane();
+        new_lane->load(*l_lane_it,this);
+        this->lanes[new_lane->get_id()]=new_lane;
+      }catch(CException &e){
+        std::cout << e.what() << std::endl;
+      }
+    }
+  }
+  // add road nodes
+  for(geom_it=road_info->planView().geometry().begin(); geom_it!=road_info->planView().geometry().end(); ++geom_it)
+  {
+    lane_offset=0.0;
+    for(unsigned int i=-1;i>=-this->num_right_lines;i--)
+    {
+      new_node=new COpendriveRoadNode();
+      this->lanes[i]->set_offset(lane_offset);
+      new_node->load(*geom_it,this->lanes[i]);
+      this->lanes[i]->add_node(new_node);
+      lane_offset-=this->lanes[i]->get_width();
+    }
+    lane_offset=0.0;
+    for(unsigned int i=1;i<=this->num_left_lines;i++)
+    {
+      new_node=new COpendriveRoadNode();
+      this->lanes[i]->set_offset(lane_offset);
+      new_node->load(*geom_it,this->lanes[i]);
+      this->lanes[i]->add_node(new_node);
+      lane_offset+=this->lanes[i]->get_width();
+    }
+  }
+}
+
+std::string COpendriveRoadSegment::get_name(void)
+{
+  return this->name;
+}
+
+unsigned int COpendriveRoadSegment::get_id(void)
+{
+  return this->id;
+}
+
+unsigned int COpendriveRoadSegment::get_num_right_lanes(void)
+{
+  return this->num_right_lanes;
+}
+
+unsigned int COpendriveRoadSegment::get_num_left_lanes(void)
+{
+  return this->num_left_lanes;
+}
+
+const COpendriveLane &COpendriveRoadSegment::get_lane(int index)
+{
+  if(index<-this->num_right_lanes || index>this->num_left_lanes)
+    CException(_HERE_,"invalid lane index");
+  else
+    return *this->lanes[index];
+}
+
+unsigned int COpendriveRoadSegment::get_num_signals(void)
+{
+  return this->signals.size();  
+}
+
+const COpendriveSignal &COpendriveRoadSegment::get_signal(unsigned int index)
+{
+  if(index>=0 && index<this->signals.size())
+    return *this->signals[index];
+  else
+    throw CException(_HERE_,"Invalid signal index");
+}
+
+unsigned int COpendriveRoadSegment::get_num_obstacles(void)
+{
+  return this->objects.size();
+}
+
+const COpendriveObject &COpendriveRoadSegment::get_object(unsigned int index)
+{
+  if(index>=0 && index<this->objects.size())
+    return *this->objects[index];
+  else
+    throw CException(_HERE_,"Invalid object index");
+}
+
+unsigned int COpendriveRoadSegment::get_num_previous(void)
+{
+  return this->prev.size();
+}
+
+const COpendriveRoadSegment &COpendriveRoadSegment::get_previous(unsigned int index)
+{
+  if(index>=0 && index<this->prev.size())
+    return *this->prev[index];
+  else
+    throw CException(_HERE_,"Invalid previous segment index");
+}
+
+unsigned int COpendriveRoadSegment::get_num_next(void)
+{
+  return this->next.size();
+}
+
+const COpendriveRoadSegment &COpendriveRoadSegment::get_next(unsigned int index)
+{
+  if(index>=0 && index<this->next.size())
+    return *this->next[index];
+  else
+    throw CException(_HERE_,"Invalid next segment index");
+}
+
+void COpendriveRoadSegment::operator=(const COpendriveRoadSegment &object)
+{
+  COpendriveLane *lane;
+  COpendriveSignal *signal;
+  CopendriveObject *object;
+
+  this->name=object.name;
+  this->id=object.id;
+  this->lanes.clear();
+  for(unsigned int i=0;i<object.lanes.size();i++)
+  {
+    lane=new COpendriveLane(*object.lanes[i]);
+    this->lanes.push_back(lane);
+  }
+  this->signals.clear();
+  for(unsigned int i=0;i<object.signals.size();i++)
+  {
+    signal=new COpendriveSignal(*object.signals[i]);
+    this->signals.push_back(signal);
+  }
+  this->objects.clear();
+  for(unsigned int i=0;i<object.objects.size();i++)
+  {
+    object=new COpendriveObject(*object.objects[i]);
+    this->objects.push_back(object);
+  }
+  this->next.resize(object.next.size());
+  for(unsigned int i=0;i<object.next.size();i++)
+    this->next[i]=object.next[i];
+  this->next.resize(object.prev.size());
+  for(unsigned int i=0;i<object.prev.size();i++)
+    this->prev[i]=object.prev[i];
+}
+
+friend std::ostream& operator<<(std::ostream& out, COpendriveRoadsegment &segment)
+{
+
+}
+
+COpendriveRoadSegment::~COpendriveRoadSegment()
+{
+  this->name="";
+  this->id=-1;
+  for(unsigned int i=-this->num_right_lanes;i<=this->num_left_lines && i!=0;i++)
+  {
+    delete this->lanes[i];
+    this->lanes[i]=NULL;
+  }
+  this->lanes.clear();
+  this->num_left_lanes=0;
+  this->num_right_lanes=0;
+  for(unsigned int i=0;i<this->signals.size();i++)
+  {
+    delete this->signals[i];
+    this->signals[i]=NULL;
+  }
+  this->signals.clear();
+  for(unsigned int i=0;i<this->objects.size();i++)
+  {
+    delete this->objects[i];
+    this->objects[i]=NULL;
+  }
+  this->objects.clear();
+  this->next.clear();
+  this->prev.clear();
+}
+
diff --git a/src/opendrive_signal.cpp b/src/opendrive_signal.cpp
new file mode 100644
index 0000000..39f1aab
--- /dev/null
+++ b/src/opendrive_signal.cpp
@@ -0,0 +1,117 @@
+#include "opendrive_signal.h"
+#include <cmath>
+
+COpendriveSignal::COpendriveSignal()
+{
+  this->id=-1;
+  this->pose.s=0.0;
+  this->pose.t=0.0;
+  this->pose.heading=0.0;
+  this->type="";
+  this->sub_type="";
+  this->value=0;
+  this->text="";
+}
+
+COpendriveSignal::COpendriveSignal(const COpendriveSignal &object)
+{
+  this->id=object.id;
+  this->pose.s=object.pose.s;
+  this->pose.t=object.pose.t;
+  this->pose.heading=object.pose.heading;
+  this->type=object.type;
+  this->sub_type=object.sub_type;
+  this->value=object.value;
+  this->text=object.text;
+}
+
+COpendriveSignal::COpendriveSignal(int id, double s, double t, double heading, std::string type, std::string sub_type, int value, std::string text, bool reverse)
+{
+  this->id=id;
+  this->pose.s=s;
+  this->pose.t=t;
+  this->pose.heading=normalize_angle(heading + (reverse ? M_PI : 0.0));
+  this->type=type;
+  this->sub_type=sub_type;
+  this->value=value;
+  this->text=text;
+}
+
+void COpendriveSignal::load(std::unique_ptr<signals::signal_type> &signal_info)
+{
+  std::stringstream ss(signal_info->id().get());
+  ss >> this->id;
+  this->pose.s = (signal_info->s().present() ? signal_info->s().get() : 0.0);
+  this->pose.t = (signal_info->t().present() ? signal_info->t().get() : 0.0);
+  this->pose.heading = (signal_info->hOffset().present() ? signal_info->hOffset().get() : 0.0);
+  this->type = (signal_info->type().present() ? signal_info->type().get() : "");
+  this->sub_type = (signal_info->subtype().present() ? signal_info->subtype().get() : "");
+  this->value = (signal_info->value().present() ? signal_info->value().get() : 0.0);
+  this->text = (signal_info->text().present() ? signal_info->text().get() : "");
+  bool reverse = false;
+  if (signal_info->orientation().present() && signal_info->orientation().get() == orientation::cxx_1)
+    reverse = true;
+  this->pose.heading = normalize_angle(this->pose.heading + (reverse ? M_PI : 0.0));
+}
+
+int COpendriveSignal::get_id(void)
+{
+  return this->id;
+}
+
+TOpendriveTrackPoint COpendriveSignal::get_pose(void)
+{
+  return this->pose;
+}
+
+void COpendriveSignal::get_type(std::string &type, std::string &sub_type)
+{
+  type=this->type;
+  sub_type=this->sub_type;
+}
+
+int COpendriveSignal::get_value(void)
+{
+  return this->value;
+}
+
+std::string COpendriveSignal::get_text(void)
+{
+  return this->text;
+}
+
+void COpendriveSignal::operator=(const COpendriveSignal &object)
+{
+  this->id=object.id;
+  this->pose.s=object.pose.s;
+  this->pose.t=object.pose.t;
+  this->pose.heading=object.pose.heading;
+  this->type=object.type;
+  this->sub_type=object.sub_type;
+  this->value=object.value;
+  this->text=object.text;
+}
+
+std::ostream& operator<<(std::ostream& out, COpendriveSignal &signal)
+{
+  out << "  Signal id = " << signal.id << std::endl;
+  out << "    type = " << signal.type << "," << signal.sub_type << std::endl;
+  out << "    value = " << signal.value << std::endl;
+  out << "    text = " << signal.text << std::endl;
+  out << "    pose: s = " << signal.pose.s << ", t = " << signal.pose.t << ", heading = " << signal.pose.heading << std::endl;
+
+  return out;
+}
+
+COpendriveSignal::~COpendriveSignal()
+{
+  this->id=-1;
+  this->pose.s=0.0;
+  this->pose.t=0.0;
+  this->pose.heading=0.0;
+  this->type="";
+  this->sub_type="";
+  this->value=0;
+  this->text="";
+}
+
diff --git a/src/opendrive_spiral.cpp b/src/opendrive_spiral.cpp
new file mode 100644
index 0000000..5407939
--- /dev/null
+++ b/src/opendrive_spiral.cpp
@@ -0,0 +1,66 @@
+#include "opendrive_spiral.h"
+
+COpendriveSpiral::COpendriveSpiral()
+{
+  this->start_curvature=0.0;
+  this->end_curvature=0.0;
+}
+
+COpendriveSpiral::COpendriveSpiral(double min_s, double max_s, double x, double y, double heading,double start_curv,double end_curv) : COpendriveGeometry(min_s,max_s,x,y,heading)
+{
+  this->start_curvature=start_curv;
+  this->end_curvature=end_curv;
+}
+
+COpendriveSpiral::COpendriveSpiral(const COpendriveSpiral &object) : COpendriveGeometry(object)
+{
+  this->start_curvature=object.start_curvature;
+  this->end_curvature=object.end_curvature;
+}
+
+bool COpendriveSpiral::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local)
+{
+  return false;
+}
+
+void COpendriveSpiral::print(std::ostream &out)
+{
+  out << "  start_curvature = " << this->start_curvature << ", end_curvature = " << this->end_curvature << std::endl;
+}
+
+void COpendriveSpiral::load_params(const planView::geometry_type &geometry_info)
+{
+  this->start_curvature = (geometry_info.spiral().get().curvStart().present() ? geometry_info.spiral().get().curvStart().get() : 0.0);
+  this->end_curvature = (geometry_info.spiral().get().curvEnd().present() ? geometry_info.spiral().get().curvEnd().get() : 0.0);
+}
+
+COpendriveGeometry *COpendriveSpiral::clone(void)
+{
+  COpendriveSpiral *new_spiral=new COpendriveSpiral(*this);
+
+  return new_spiral;
+}
+
+double COpendriveSpiral::get_start_curvature(void)
+{
+  return this->start_curvature;
+}
+
+double COpendriveSpiral::get_end_curvature(void)
+{
+  return this->end_curvature;
+}
+
+void COpendriveSpiral::operator=(const COpendriveSpiral &object)
+{
+  COpendriveGeometry::operator=(object);
+  this->start_curvature=object.start_curvature;
+  this->end_curvature=object.end_curvature;
+}
+
+COpendriveSpiral::~COpendriveSpiral()
+{
+  this->start_curvature=0.0;
+  this->end_curvature=0.0;
+}
+
diff --git a/src/xml/CMakeLists.txt b/src/xml/CMakeLists.txt
new file mode 100644
index 0000000..c2bf844
--- /dev/null
+++ b/src/xml/CMakeLists.txt
@@ -0,0 +1,47 @@
+#check the existance of the xsd library
+IF(EXISTS "/usr/include/xsd/cxx")
+   SET(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -D_HAVE_XSD" PARENT_SCOPE)
+   SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -D_HAVE_XSD" PARENT_SCOPE)
+   SET(XSD_FOUND TRUE) 
+   MESSAGE(STATUS "Found the XML library ... adding support for XML files")
+   FIND_LIBRARY(XSD_LIBRARIES
+      NAMES xerces-c
+      PATHS /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu/)
+   SET(XSD_LIBRARY    ${XSD_LIBRARIES})
+ELSE(EXISTS "/usr/include/xsd/cxx")
+   MESSAGE(STATUS "XML library not found ... it will be impossible to handle XML files")
+ENDIF(EXISTS "/usr/include/xsd/cxx")
+
+IF(XSD_FOUND)
+   SET(XSD_LIBRARIES ${XSD_LIBRARIES} PARENT_SCOPE)
+   SET(XSD_LIBRARY ${XSD_LIBRARY} PARENT_SCOPE)
+
+   SET(XSD_PATH ${CMAKE_CURRENT_SOURCE_DIR})
+   SET(XSD_FILES OpenDRIVE_1.4H.xsd)
+
+   IF(XSD_FILES)
+      FOREACH(xsd_file ${XSD_FILES})
+         STRING(REGEX REPLACE "xsd" "cxx" xsd_source ${xsd_file})
+         SET(XSD_SOURCES_INT ${XSD_SOURCES_INT} ${XSD_PATH}/${xsd_source})
+         SET(XSD_SOURCES ${XSD_SOURCES} ${XSD_PATH}/${xsd_source})
+         STRING(REGEX REPLACE "xsd" "hxx" xsd_header ${xsd_file})
+         SET(XSD_HEADERS_INT ${XSD_HEADERS_INT} ${XSD_PATH}/${xsd_header})
+         SET(XSD_HEADERS ${XSD_HEADERS} ${XSD_PATH}/${xsd_header})
+         SET(XSD_PATH_FILES ${XSD_PATH_FILES} ${XSD_PATH}/${xsd_file})
+      ENDFOREACH(xsd_file)
+
+      SET(XSD_SOURCES ${XSD_SOURCES_INT} PARENT_SCOPE)
+      SET(XSD_HEADERS ${XSD_HEADERS_INT} PARENT_SCOPE)
+
+      ADD_CUSTOM_TARGET(xsd_files_gen DEPENDS ${XSD_SOURCES_INT})
+      ADD_CUSTOM_COMMAND(
+         OUTPUT ${XSD_SOURCES_INT}
+         COMMAND xsdcxx cxx-tree --std c++11 --generate-serialization --reserved-name access=parkingSpace_access --reserved-name link=lane_link ${XSD_FILES}
+         WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
+         DEPENDS ${XSD_PATH_FILES}
+         COMMENT "Parsing the xml template file ${XSD_FILES}")
+
+      INSTALL(FILES ${XSD_PATH_FILES} DESTINATION include/iri/${PROJECT_NAME}/xml)
+      INSTALL(FILES ${XSD_HEADERS_INT} DESTINATION include/iri/${PROJECT_NAME}/xml)
+   ENDIF(XSD_FILES)
+ENDIF(XSD_FOUND)
diff --git a/src/xml/OpenDRIVE_1.4H.cxx b/src/xml/OpenDRIVE_1.4H.cxx
new file mode 100644
index 0000000..12f4b1c
--- /dev/null
+++ b/src/xml/OpenDRIVE_1.4H.cxx
@@ -0,0 +1,36361 @@
+// Copyright (c) 2005-2014 Code Synthesis Tools CC
+//
+// This program was generated by CodeSynthesis XSD, an XML Schema to
+// C++ data binding compiler.
+//
+// This program is free software; you can redistribute it and/or modify
+// it under the terms of the GNU General Public License version 2 as
+// published by the Free Software Foundation.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program; if not, write to the Free Software
+// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+//
+// In addition, as a special exception, Code Synthesis Tools CC gives
+// permission to link this program with the Xerces-C++ library (or with
+// modified versions of Xerces-C++ that use the same license as Xerces-C++),
+// and distribute linked combinations including the two. You must obey
+// the GNU General Public License version 2 in all respects for all of
+// the code used other than Xerces-C++. If you modify this copy of the
+// program, you may extend this exception to your version of the program,
+// but you are not obligated to do so. If you do not wish to do so, delete
+// this exception statement from your version.
+//
+// Furthermore, Code Synthesis Tools CC makes a special exception for
+// the Free/Libre and Open Source Software (FLOSS) which is described
+// in the accompanying FLOSSE file.
+//
+
+// Begin prologue.
+//
+//
+// End prologue.
+
+#include <xsd/cxx/pre.hxx>
+
+#include "OpenDRIVE_1.4H.hxx"
+
+// elementType
+// 
+
+elementType::
+elementType (value v)
+: ::xml_schema::string (_xsd_elementType_literals_[v])
+{
+}
+
+elementType::
+elementType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+elementType::
+elementType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+elementType::
+elementType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+elementType::
+elementType (const elementType& v,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+elementType& elementType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_elementType_literals_[v]);
+
+  return *this;
+}
+
+
+// max
+//
+
+max::
+max (const char* s)
+: ::xml_schema::string (s)
+{
+}
+
+max::
+max (const ::std::string& s)
+: ::xml_schema::string (s)
+{
+}
+
+max::
+max (const max& o,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (o, f, c)
+{
+}
+
+// contactPoint
+// 
+
+contactPoint::
+contactPoint (value v)
+: ::xml_schema::string (_xsd_contactPoint_literals_[v])
+{
+}
+
+contactPoint::
+contactPoint (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+contactPoint::
+contactPoint (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+contactPoint::
+contactPoint (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+contactPoint::
+contactPoint (const contactPoint& v,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+contactPoint& contactPoint::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_contactPoint_literals_[v]);
+
+  return *this;
+}
+
+
+// side
+// 
+
+side::
+side (value v)
+: ::xml_schema::string (_xsd_side_literals_[v])
+{
+}
+
+side::
+side (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+side::
+side (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+side::
+side (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+side::
+side (const side& v,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+side& side::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_side_literals_[v]);
+
+  return *this;
+}
+
+
+// direction
+// 
+
+direction::
+direction (value v)
+: ::xml_schema::string (_xsd_direction_literals_[v])
+{
+}
+
+direction::
+direction (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+direction::
+direction (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+direction::
+direction (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+direction::
+direction (const direction& v,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+direction& direction::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_direction_literals_[v]);
+
+  return *this;
+}
+
+
+// roadType
+// 
+
+roadType::
+roadType (value v)
+: ::xml_schema::string (_xsd_roadType_literals_[v])
+{
+}
+
+roadType::
+roadType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+roadType::
+roadType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+roadType::
+roadType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+roadType::
+roadType (const roadType& v,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+roadType& roadType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_roadType_literals_[v]);
+
+  return *this;
+}
+
+
+// unit
+// 
+
+unit::
+unit (value v)
+: ::xml_schema::string (_xsd_unit_literals_[v])
+{
+}
+
+unit::
+unit (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+unit::
+unit (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+unit::
+unit (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+unit::
+unit (const unit& v,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+unit& unit::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_unit_literals_[v]);
+
+  return *this;
+}
+
+
+// pRange
+// 
+
+pRange::
+pRange (value v)
+: ::xml_schema::string (_xsd_pRange_literals_[v])
+{
+}
+
+pRange::
+pRange (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+pRange::
+pRange (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+pRange::
+pRange (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+pRange::
+pRange (const pRange& v,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+pRange& pRange::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_pRange_literals_[v]);
+
+  return *this;
+}
+
+
+// crossfallSide
+// 
+
+crossfallSide::
+crossfallSide (value v)
+: ::xml_schema::string (_xsd_crossfallSide_literals_[v])
+{
+}
+
+crossfallSide::
+crossfallSide (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+crossfallSide::
+crossfallSide (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+crossfallSide::
+crossfallSide (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+crossfallSide::
+crossfallSide (const crossfallSide& v,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+crossfallSide& crossfallSide::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_crossfallSide_literals_[v]);
+
+  return *this;
+}
+
+
+// singleSide
+// 
+
+singleSide::
+singleSide (value v)
+: ::xml_schema::string (_xsd_singleSide_literals_[v])
+{
+}
+
+singleSide::
+singleSide (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+singleSide::
+singleSide (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+singleSide::
+singleSide (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+singleSide::
+singleSide (const singleSide& v,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+singleSide& singleSide::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_singleSide_literals_[v]);
+
+  return *this;
+}
+
+
+// laneType
+// 
+
+laneType::
+laneType (value v)
+: ::xml_schema::string (_xsd_laneType_literals_[v])
+{
+}
+
+laneType::
+laneType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+laneType::
+laneType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+laneType::
+laneType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+laneType::
+laneType (const laneType& v,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+laneType& laneType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_laneType_literals_[v]);
+
+  return *this;
+}
+
+
+// roadmarkType
+// 
+
+roadmarkType::
+roadmarkType (value v)
+: ::xml_schema::string (_xsd_roadmarkType_literals_[v])
+{
+}
+
+roadmarkType::
+roadmarkType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+roadmarkType::
+roadmarkType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+roadmarkType::
+roadmarkType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+roadmarkType::
+roadmarkType (const roadmarkType& v,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+roadmarkType& roadmarkType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_roadmarkType_literals_[v]);
+
+  return *this;
+}
+
+
+// weight
+// 
+
+weight::
+weight (value v)
+: ::xml_schema::string (_xsd_weight_literals_[v])
+{
+}
+
+weight::
+weight (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+weight::
+weight (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+weight::
+weight (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+weight::
+weight (const weight& v,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+weight& weight::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_weight_literals_[v]);
+
+  return *this;
+}
+
+
+// color
+// 
+
+color::
+color (value v)
+: ::xml_schema::string (_xsd_color_literals_[v])
+{
+}
+
+color::
+color (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+color::
+color (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+color::
+color (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+color::
+color (const color& v,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+color& color::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_color_literals_[v]);
+
+  return *this;
+}
+
+
+// restriction
+// 
+
+restriction::
+restriction (value v)
+: ::xml_schema::string (_xsd_restriction_literals_[v])
+{
+}
+
+restriction::
+restriction (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+restriction::
+restriction (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+restriction::
+restriction (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+restriction::
+restriction (const restriction& v,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+restriction& restriction::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_restriction_literals_[v]);
+
+  return *this;
+}
+
+
+// laneChange
+// 
+
+laneChange::
+laneChange (value v)
+: ::xml_schema::string (_xsd_laneChange_literals_[v])
+{
+}
+
+laneChange::
+laneChange (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+laneChange::
+laneChange (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+laneChange::
+laneChange (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+laneChange::
+laneChange (const laneChange& v,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+laneChange& laneChange::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_laneChange_literals_[v]);
+
+  return *this;
+}
+
+
+// rule
+// 
+
+rule::
+rule (value v)
+: ::xml_schema::string (_xsd_rule_literals_[v])
+{
+}
+
+rule::
+rule (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+rule::
+rule (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+rule::
+rule (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+rule::
+rule (const rule& v,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+rule& rule::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_rule_literals_[v]);
+
+  return *this;
+}
+
+
+// orientation
+// 
+
+orientation::
+orientation (value v)
+: ::xml_schema::string (_xsd_orientation_literals_[v])
+{
+}
+
+orientation::
+orientation (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+orientation::
+orientation (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+orientation::
+orientation (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+orientation::
+orientation (const orientation& v,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+orientation& orientation::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_orientation_literals_[v]);
+
+  return *this;
+}
+
+
+// tunnelType
+// 
+
+tunnelType::
+tunnelType (value v)
+: ::xml_schema::string (_xsd_tunnelType_literals_[v])
+{
+}
+
+tunnelType::
+tunnelType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+tunnelType::
+tunnelType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+tunnelType::
+tunnelType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+tunnelType::
+tunnelType (const tunnelType& v,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+tunnelType& tunnelType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_tunnelType_literals_[v]);
+
+  return *this;
+}
+
+
+// bridgeType
+// 
+
+bridgeType::
+bridgeType (value v)
+: ::xml_schema::string (_xsd_bridgeType_literals_[v])
+{
+}
+
+bridgeType::
+bridgeType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+bridgeType::
+bridgeType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+bridgeType::
+bridgeType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+bridgeType::
+bridgeType (const bridgeType& v,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+bridgeType& bridgeType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_bridgeType_literals_[v]);
+
+  return *this;
+}
+
+
+// parkingSpace_access
+// 
+
+parkingSpace_access::
+parkingSpace_access (value v)
+: ::xml_schema::string (_xsd_parkingSpace_access_literals_[v])
+{
+}
+
+parkingSpace_access::
+parkingSpace_access (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpace_access::
+parkingSpace_access (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpace_access::
+parkingSpace_access (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpace_access::
+parkingSpace_access (const parkingSpace_access& v,
+                     ::xml_schema::flags f,
+                     ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+parkingSpace_access& parkingSpace_access::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_parkingSpace_access_literals_[v]);
+
+  return *this;
+}
+
+
+// parkingSpacemarkingSide
+// 
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (value v)
+: ::xml_schema::string (_xsd_parkingSpacemarkingSide_literals_[v])
+{
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const parkingSpacemarkingSide& v,
+                         ::xml_schema::flags f,
+                         ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+parkingSpacemarkingSide& parkingSpacemarkingSide::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_parkingSpacemarkingSide_literals_[v]);
+
+  return *this;
+}
+
+
+// dynamic
+// 
+
+dynamic::
+dynamic (value v)
+: ::xml_schema::string (_xsd_dynamic_literals_[v])
+{
+}
+
+dynamic::
+dynamic (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+dynamic::
+dynamic (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+dynamic::
+dynamic (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+dynamic::
+dynamic (const dynamic& v,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+dynamic& dynamic::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_dynamic_literals_[v]);
+
+  return *this;
+}
+
+
+// surfaceOrientation
+// 
+
+surfaceOrientation::
+surfaceOrientation (value v)
+: ::xml_schema::string (_xsd_surfaceOrientation_literals_[v])
+{
+}
+
+surfaceOrientation::
+surfaceOrientation (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+surfaceOrientation::
+surfaceOrientation (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+surfaceOrientation::
+surfaceOrientation (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+surfaceOrientation::
+surfaceOrientation (const surfaceOrientation& v,
+                    ::xml_schema::flags f,
+                    ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+surfaceOrientation& surfaceOrientation::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_surfaceOrientation_literals_[v]);
+
+  return *this;
+}
+
+
+// mode
+// 
+
+mode::
+mode (value v)
+: ::xml_schema::string (_xsd_mode_literals_[v])
+{
+}
+
+mode::
+mode (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+mode::
+mode (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+mode::
+mode (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+mode::
+mode (const mode& v,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+mode& mode::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_mode_literals_[v]);
+
+  return *this;
+}
+
+
+// purpose
+// 
+
+purpose::
+purpose (value v)
+: ::xml_schema::string (_xsd_purpose_literals_[v])
+{
+}
+
+purpose::
+purpose (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+purpose::
+purpose (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+purpose::
+purpose (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+purpose::
+purpose (const purpose& v,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+purpose& purpose::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_purpose_literals_[v]);
+
+  return *this;
+}
+
+
+// position
+// 
+
+position::
+position (value v)
+: ::xml_schema::string (_xsd_position_literals_[v])
+{
+}
+
+position::
+position (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+position::
+position (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+position::
+position (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+position::
+position (const position& v,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+position& position::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_position_literals_[v]);
+
+  return *this;
+}
+
+
+// dir
+// 
+
+dir::
+dir (value v)
+: ::xml_schema::string (_xsd_dir_literals_[v])
+{
+}
+
+dir::
+dir (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+dir::
+dir (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+dir::
+dir (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+dir::
+dir (const dir& v,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+dir& dir::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_dir_literals_[v]);
+
+  return *this;
+}
+
+
+// junctionGroupType
+// 
+
+junctionGroupType::
+junctionGroupType (value v)
+: ::xml_schema::string (_xsd_junctionGroupType_literals_[v])
+{
+}
+
+junctionGroupType::
+junctionGroupType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+junctionGroupType::
+junctionGroupType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+junctionGroupType::
+junctionGroupType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+junctionGroupType::
+junctionGroupType (const junctionGroupType& v,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+junctionGroupType& junctionGroupType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_junctionGroupType_literals_[v]);
+
+  return *this;
+}
+
+
+// stationType
+// 
+
+stationType::
+stationType (value v)
+: ::xml_schema::string (_xsd_stationType_literals_[v])
+{
+}
+
+stationType::
+stationType (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+stationType::
+stationType (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+stationType::
+stationType (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+stationType::
+stationType (const stationType& v,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+stationType& stationType::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_stationType_literals_[v]);
+
+  return *this;
+}
+
+
+// userData
+// 
+
+const userData::code_optional& userData::
+code () const
+{
+  return this->code_;
+}
+
+userData::code_optional& userData::
+code ()
+{
+  return this->code_;
+}
+
+void userData::
+code (const code_type& x)
+{
+  this->code_.set (x);
+}
+
+void userData::
+code (const code_optional& x)
+{
+  this->code_ = x;
+}
+
+void userData::
+code (::std::unique_ptr< code_type > x)
+{
+  this->code_.set (std::move (x));
+}
+
+const userData::value_optional& userData::
+value () const
+{
+  return this->value_;
+}
+
+userData::value_optional& userData::
+value ()
+{
+  return this->value_;
+}
+
+void userData::
+value (const value_type& x)
+{
+  this->value_.set (x);
+}
+
+void userData::
+value (const value_optional& x)
+{
+  this->value_ = x;
+}
+
+void userData::
+value (::std::unique_ptr< value_type > x)
+{
+  this->value_.set (std::move (x));
+}
+
+
+// include
+// 
+
+const include::file_optional& include::
+file () const
+{
+  return this->file_;
+}
+
+include::file_optional& include::
+file ()
+{
+  return this->file_;
+}
+
+void include::
+file (const file_type& x)
+{
+  this->file_.set (x);
+}
+
+void include::
+file (const file_optional& x)
+{
+  this->file_ = x;
+}
+
+void include::
+file (::std::unique_ptr< file_type > x)
+{
+  this->file_.set (std::move (x));
+}
+
+
+// laneValidity
+// 
+
+const laneValidity::userData_sequence& laneValidity::
+userData () const
+{
+  return this->userData_;
+}
+
+laneValidity::userData_sequence& laneValidity::
+userData ()
+{
+  return this->userData_;
+}
+
+void laneValidity::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const laneValidity::include_sequence& laneValidity::
+include () const
+{
+  return this->include_;
+}
+
+laneValidity::include_sequence& laneValidity::
+include ()
+{
+  return this->include_;
+}
+
+void laneValidity::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const laneValidity::fromLane_optional& laneValidity::
+fromLane () const
+{
+  return this->fromLane_;
+}
+
+laneValidity::fromLane_optional& laneValidity::
+fromLane ()
+{
+  return this->fromLane_;
+}
+
+void laneValidity::
+fromLane (const fromLane_type& x)
+{
+  this->fromLane_.set (x);
+}
+
+void laneValidity::
+fromLane (const fromLane_optional& x)
+{
+  this->fromLane_ = x;
+}
+
+const laneValidity::toLane_optional& laneValidity::
+toLane () const
+{
+  return this->toLane_;
+}
+
+laneValidity::toLane_optional& laneValidity::
+toLane ()
+{
+  return this->toLane_;
+}
+
+void laneValidity::
+toLane (const toLane_type& x)
+{
+  this->toLane_.set (x);
+}
+
+void laneValidity::
+toLane (const toLane_optional& x)
+{
+  this->toLane_ = x;
+}
+
+
+// parkingSpace
+// 
+
+const parkingSpace::marking_sequence& parkingSpace::
+marking () const
+{
+  return this->marking_;
+}
+
+parkingSpace::marking_sequence& parkingSpace::
+marking ()
+{
+  return this->marking_;
+}
+
+void parkingSpace::
+marking (const marking_sequence& s)
+{
+  this->marking_ = s;
+}
+
+const parkingSpace::userData_sequence& parkingSpace::
+userData () const
+{
+  return this->userData_;
+}
+
+parkingSpace::userData_sequence& parkingSpace::
+userData ()
+{
+  return this->userData_;
+}
+
+void parkingSpace::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const parkingSpace::include_sequence& parkingSpace::
+include () const
+{
+  return this->include_;
+}
+
+parkingSpace::include_sequence& parkingSpace::
+include ()
+{
+  return this->include_;
+}
+
+void parkingSpace::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const parkingSpace::access_optional& parkingSpace::
+parkingSpace_access () const
+{
+  return this->parkingSpace_access_;
+}
+
+parkingSpace::access_optional& parkingSpace::
+parkingSpace_access ()
+{
+  return this->parkingSpace_access_;
+}
+
+void parkingSpace::
+parkingSpace_access (const access_type& x)
+{
+  this->parkingSpace_access_.set (x);
+}
+
+void parkingSpace::
+parkingSpace_access (const access_optional& x)
+{
+  this->parkingSpace_access_ = x;
+}
+
+void parkingSpace::
+parkingSpace_access (::std::unique_ptr< access_type > x)
+{
+  this->parkingSpace_access_.set (std::move (x));
+}
+
+const parkingSpace::restrictions_optional& parkingSpace::
+restrictions () const
+{
+  return this->restrictions_;
+}
+
+parkingSpace::restrictions_optional& parkingSpace::
+restrictions ()
+{
+  return this->restrictions_;
+}
+
+void parkingSpace::
+restrictions (const restrictions_type& x)
+{
+  this->restrictions_.set (x);
+}
+
+void parkingSpace::
+restrictions (const restrictions_optional& x)
+{
+  this->restrictions_ = x;
+}
+
+void parkingSpace::
+restrictions (::std::unique_ptr< restrictions_type > x)
+{
+  this->restrictions_.set (std::move (x));
+}
+
+
+// lane
+// 
+
+const lane::link_optional& lane::
+lane_link () const
+{
+  return this->lane_link_;
+}
+
+lane::link_optional& lane::
+lane_link ()
+{
+  return this->lane_link_;
+}
+
+void lane::
+lane_link (const link_type& x)
+{
+  this->lane_link_.set (x);
+}
+
+void lane::
+lane_link (const link_optional& x)
+{
+  this->lane_link_ = x;
+}
+
+void lane::
+lane_link (::std::unique_ptr< link_type > x)
+{
+  this->lane_link_.set (std::move (x));
+}
+
+const lane::width_sequence& lane::
+width () const
+{
+  return this->width_;
+}
+
+lane::width_sequence& lane::
+width ()
+{
+  return this->width_;
+}
+
+void lane::
+width (const width_sequence& s)
+{
+  this->width_ = s;
+}
+
+const lane::border_sequence& lane::
+border () const
+{
+  return this->border_;
+}
+
+lane::border_sequence& lane::
+border ()
+{
+  return this->border_;
+}
+
+void lane::
+border (const border_sequence& s)
+{
+  this->border_ = s;
+}
+
+const lane::roadMark_sequence& lane::
+roadMark () const
+{
+  return this->roadMark_;
+}
+
+lane::roadMark_sequence& lane::
+roadMark ()
+{
+  return this->roadMark_;
+}
+
+void lane::
+roadMark (const roadMark_sequence& s)
+{
+  this->roadMark_ = s;
+}
+
+const lane::material_sequence& lane::
+material () const
+{
+  return this->material_;
+}
+
+lane::material_sequence& lane::
+material ()
+{
+  return this->material_;
+}
+
+void lane::
+material (const material_sequence& s)
+{
+  this->material_ = s;
+}
+
+const lane::visibility_sequence& lane::
+visibility () const
+{
+  return this->visibility_;
+}
+
+lane::visibility_sequence& lane::
+visibility ()
+{
+  return this->visibility_;
+}
+
+void lane::
+visibility (const visibility_sequence& s)
+{
+  this->visibility_ = s;
+}
+
+const lane::speed_sequence& lane::
+speed () const
+{
+  return this->speed_;
+}
+
+lane::speed_sequence& lane::
+speed ()
+{
+  return this->speed_;
+}
+
+void lane::
+speed (const speed_sequence& s)
+{
+  this->speed_ = s;
+}
+
+const lane::access_sequence& lane::
+parkingSpace_access () const
+{
+  return this->parkingSpace_access_;
+}
+
+lane::access_sequence& lane::
+parkingSpace_access ()
+{
+  return this->parkingSpace_access_;
+}
+
+void lane::
+parkingSpace_access (const access_sequence& s)
+{
+  this->parkingSpace_access_ = s;
+}
+
+const lane::height_sequence& lane::
+height () const
+{
+  return this->height_;
+}
+
+lane::height_sequence& lane::
+height ()
+{
+  return this->height_;
+}
+
+void lane::
+height (const height_sequence& s)
+{
+  this->height_ = s;
+}
+
+const lane::rule_sequence& lane::
+rule () const
+{
+  return this->rule_;
+}
+
+lane::rule_sequence& lane::
+rule ()
+{
+  return this->rule_;
+}
+
+void lane::
+rule (const rule_sequence& s)
+{
+  this->rule_ = s;
+}
+
+const lane::userData_sequence& lane::
+userData () const
+{
+  return this->userData_;
+}
+
+lane::userData_sequence& lane::
+userData ()
+{
+  return this->userData_;
+}
+
+void lane::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const lane::include_sequence& lane::
+include () const
+{
+  return this->include_;
+}
+
+lane::include_sequence& lane::
+include ()
+{
+  return this->include_;
+}
+
+void lane::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const lane::id_optional& lane::
+id () const
+{
+  return this->id_;
+}
+
+lane::id_optional& lane::
+id ()
+{
+  return this->id_;
+}
+
+void lane::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void lane::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+const lane::type_optional& lane::
+type () const
+{
+  return this->type_;
+}
+
+lane::type_optional& lane::
+type ()
+{
+  return this->type_;
+}
+
+void lane::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void lane::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void lane::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const lane::level_optional& lane::
+level () const
+{
+  return this->level_;
+}
+
+lane::level_optional& lane::
+level ()
+{
+  return this->level_;
+}
+
+void lane::
+level (const level_type& x)
+{
+  this->level_.set (x);
+}
+
+void lane::
+level (const level_optional& x)
+{
+  this->level_ = x;
+}
+
+void lane::
+level (::std::unique_ptr< level_type > x)
+{
+  this->level_.set (std::move (x));
+}
+
+
+// centerLane
+// 
+
+const centerLane::link_optional& centerLane::
+lane_link () const
+{
+  return this->lane_link_;
+}
+
+centerLane::link_optional& centerLane::
+lane_link ()
+{
+  return this->lane_link_;
+}
+
+void centerLane::
+lane_link (const link_type& x)
+{
+  this->lane_link_.set (x);
+}
+
+void centerLane::
+lane_link (const link_optional& x)
+{
+  this->lane_link_ = x;
+}
+
+void centerLane::
+lane_link (::std::unique_ptr< link_type > x)
+{
+  this->lane_link_.set (std::move (x));
+}
+
+const centerLane::roadMark_sequence& centerLane::
+roadMark () const
+{
+  return this->roadMark_;
+}
+
+centerLane::roadMark_sequence& centerLane::
+roadMark ()
+{
+  return this->roadMark_;
+}
+
+void centerLane::
+roadMark (const roadMark_sequence& s)
+{
+  this->roadMark_ = s;
+}
+
+const centerLane::userData_sequence& centerLane::
+userData () const
+{
+  return this->userData_;
+}
+
+centerLane::userData_sequence& centerLane::
+userData ()
+{
+  return this->userData_;
+}
+
+void centerLane::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const centerLane::include_sequence& centerLane::
+include () const
+{
+  return this->include_;
+}
+
+centerLane::include_sequence& centerLane::
+include ()
+{
+  return this->include_;
+}
+
+void centerLane::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const centerLane::id_optional& centerLane::
+id () const
+{
+  return this->id_;
+}
+
+centerLane::id_optional& centerLane::
+id ()
+{
+  return this->id_;
+}
+
+void centerLane::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void centerLane::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+const centerLane::type_optional& centerLane::
+type () const
+{
+  return this->type_;
+}
+
+centerLane::type_optional& centerLane::
+type ()
+{
+  return this->type_;
+}
+
+void centerLane::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void centerLane::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void centerLane::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const centerLane::level_optional& centerLane::
+level () const
+{
+  return this->level_;
+}
+
+centerLane::level_optional& centerLane::
+level ()
+{
+  return this->level_;
+}
+
+void centerLane::
+level (const level_type& x)
+{
+  this->level_.set (x);
+}
+
+void centerLane::
+level (const level_optional& x)
+{
+  this->level_ = x;
+}
+
+void centerLane::
+level (::std::unique_ptr< level_type > x)
+{
+  this->level_.set (std::move (x));
+}
+
+
+// OpenDRIVE
+// 
+
+const OpenDRIVE::header_type& OpenDRIVE::
+header () const
+{
+  return this->header_.get ();
+}
+
+OpenDRIVE::header_type& OpenDRIVE::
+header ()
+{
+  return this->header_.get ();
+}
+
+void OpenDRIVE::
+header (const header_type& x)
+{
+  this->header_.set (x);
+}
+
+void OpenDRIVE::
+header (::std::unique_ptr< header_type > x)
+{
+  this->header_.set (std::move (x));
+}
+
+const OpenDRIVE::road_sequence& OpenDRIVE::
+road () const
+{
+  return this->road_;
+}
+
+OpenDRIVE::road_sequence& OpenDRIVE::
+road ()
+{
+  return this->road_;
+}
+
+void OpenDRIVE::
+road (const road_sequence& s)
+{
+  this->road_ = s;
+}
+
+const OpenDRIVE::controller_sequence& OpenDRIVE::
+controller () const
+{
+  return this->controller_;
+}
+
+OpenDRIVE::controller_sequence& OpenDRIVE::
+controller ()
+{
+  return this->controller_;
+}
+
+void OpenDRIVE::
+controller (const controller_sequence& s)
+{
+  this->controller_ = s;
+}
+
+const OpenDRIVE::junction_sequence& OpenDRIVE::
+junction () const
+{
+  return this->junction_;
+}
+
+OpenDRIVE::junction_sequence& OpenDRIVE::
+junction ()
+{
+  return this->junction_;
+}
+
+void OpenDRIVE::
+junction (const junction_sequence& s)
+{
+  this->junction_ = s;
+}
+
+const OpenDRIVE::junctionGroup_sequence& OpenDRIVE::
+junctionGroup () const
+{
+  return this->junctionGroup_;
+}
+
+OpenDRIVE::junctionGroup_sequence& OpenDRIVE::
+junctionGroup ()
+{
+  return this->junctionGroup_;
+}
+
+void OpenDRIVE::
+junctionGroup (const junctionGroup_sequence& s)
+{
+  this->junctionGroup_ = s;
+}
+
+const OpenDRIVE::station_sequence& OpenDRIVE::
+station () const
+{
+  return this->station_;
+}
+
+OpenDRIVE::station_sequence& OpenDRIVE::
+station ()
+{
+  return this->station_;
+}
+
+void OpenDRIVE::
+station (const station_sequence& s)
+{
+  this->station_ = s;
+}
+
+
+// max_member
+// 
+
+max_member::
+max_member (value v)
+: ::xml_schema::string (_xsd_max_member_literals_[v])
+{
+}
+
+max_member::
+max_member (const char* v)
+: ::xml_schema::string (v)
+{
+}
+
+max_member::
+max_member (const ::std::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+max_member::
+max_member (const ::xml_schema::string& v)
+: ::xml_schema::string (v)
+{
+}
+
+max_member::
+max_member (const max_member& v,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (v, f, c)
+{
+}
+
+max_member& max_member::
+operator= (value v)
+{
+  static_cast< ::xml_schema::string& > (*this) = 
+  ::xml_schema::string (_xsd_max_member_literals_[v]);
+
+  return *this;
+}
+
+
+// max_member1
+// 
+
+
+// marking
+// 
+
+const marking::side_optional& marking::
+side () const
+{
+  return this->side_;
+}
+
+marking::side_optional& marking::
+side ()
+{
+  return this->side_;
+}
+
+void marking::
+side (const side_type& x)
+{
+  this->side_.set (x);
+}
+
+void marking::
+side (const side_optional& x)
+{
+  this->side_ = x;
+}
+
+void marking::
+side (::std::unique_ptr< side_type > x)
+{
+  this->side_.set (std::move (x));
+}
+
+const marking::type_optional& marking::
+type () const
+{
+  return this->type_;
+}
+
+marking::type_optional& marking::
+type ()
+{
+  return this->type_;
+}
+
+void marking::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void marking::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void marking::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const marking::width_optional& marking::
+width () const
+{
+  return this->width_;
+}
+
+marking::width_optional& marking::
+width ()
+{
+  return this->width_;
+}
+
+void marking::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void marking::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+const marking::color_optional& marking::
+color () const
+{
+  return this->color_;
+}
+
+marking::color_optional& marking::
+color ()
+{
+  return this->color_;
+}
+
+void marking::
+color (const color_type& x)
+{
+  this->color_.set (x);
+}
+
+void marking::
+color (const color_optional& x)
+{
+  this->color_ = x;
+}
+
+void marking::
+color (::std::unique_ptr< color_type > x)
+{
+  this->color_.set (std::move (x));
+}
+
+
+// lane_link
+// 
+
+const lane_link::predecessor_optional& lane_link::
+predecessor () const
+{
+  return this->predecessor_;
+}
+
+lane_link::predecessor_optional& lane_link::
+predecessor ()
+{
+  return this->predecessor_;
+}
+
+void lane_link::
+predecessor (const predecessor_type& x)
+{
+  this->predecessor_.set (x);
+}
+
+void lane_link::
+predecessor (const predecessor_optional& x)
+{
+  this->predecessor_ = x;
+}
+
+void lane_link::
+predecessor (::std::unique_ptr< predecessor_type > x)
+{
+  this->predecessor_.set (std::move (x));
+}
+
+const lane_link::successor_optional& lane_link::
+successor () const
+{
+  return this->successor_;
+}
+
+lane_link::successor_optional& lane_link::
+successor ()
+{
+  return this->successor_;
+}
+
+void lane_link::
+successor (const successor_type& x)
+{
+  this->successor_.set (x);
+}
+
+void lane_link::
+successor (const successor_optional& x)
+{
+  this->successor_ = x;
+}
+
+void lane_link::
+successor (::std::unique_ptr< successor_type > x)
+{
+  this->successor_.set (std::move (x));
+}
+
+const lane_link::userData_sequence& lane_link::
+userData () const
+{
+  return this->userData_;
+}
+
+lane_link::userData_sequence& lane_link::
+userData ()
+{
+  return this->userData_;
+}
+
+void lane_link::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const lane_link::include_sequence& lane_link::
+include () const
+{
+  return this->include_;
+}
+
+lane_link::include_sequence& lane_link::
+include ()
+{
+  return this->include_;
+}
+
+void lane_link::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// width
+// 
+
+const width::userData_sequence& width::
+userData () const
+{
+  return this->userData_;
+}
+
+width::userData_sequence& width::
+userData ()
+{
+  return this->userData_;
+}
+
+void width::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const width::include_sequence& width::
+include () const
+{
+  return this->include_;
+}
+
+width::include_sequence& width::
+include ()
+{
+  return this->include_;
+}
+
+void width::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const width::sOffset_optional& width::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+width::sOffset_optional& width::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void width::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void width::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const width::a_optional& width::
+a () const
+{
+  return this->a_;
+}
+
+width::a_optional& width::
+a ()
+{
+  return this->a_;
+}
+
+void width::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void width::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const width::b_optional& width::
+b () const
+{
+  return this->b_;
+}
+
+width::b_optional& width::
+b ()
+{
+  return this->b_;
+}
+
+void width::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void width::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const width::c_optional& width::
+c () const
+{
+  return this->c_;
+}
+
+width::c_optional& width::
+c ()
+{
+  return this->c_;
+}
+
+void width::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void width::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const width::d_optional& width::
+d () const
+{
+  return this->d_;
+}
+
+width::d_optional& width::
+d ()
+{
+  return this->d_;
+}
+
+void width::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void width::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// border
+// 
+
+const border::userData_sequence& border::
+userData () const
+{
+  return this->userData_;
+}
+
+border::userData_sequence& border::
+userData ()
+{
+  return this->userData_;
+}
+
+void border::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const border::include_sequence& border::
+include () const
+{
+  return this->include_;
+}
+
+border::include_sequence& border::
+include ()
+{
+  return this->include_;
+}
+
+void border::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const border::sOffset_optional& border::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+border::sOffset_optional& border::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void border::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void border::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const border::a_optional& border::
+a () const
+{
+  return this->a_;
+}
+
+border::a_optional& border::
+a ()
+{
+  return this->a_;
+}
+
+void border::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void border::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const border::b_optional& border::
+b () const
+{
+  return this->b_;
+}
+
+border::b_optional& border::
+b ()
+{
+  return this->b_;
+}
+
+void border::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void border::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const border::c_optional& border::
+c () const
+{
+  return this->c_;
+}
+
+border::c_optional& border::
+c ()
+{
+  return this->c_;
+}
+
+void border::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void border::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const border::d_optional& border::
+d () const
+{
+  return this->d_;
+}
+
+border::d_optional& border::
+d ()
+{
+  return this->d_;
+}
+
+void border::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void border::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// roadMark
+// 
+
+const roadMark::type_optional& roadMark::
+type () const
+{
+  return this->type_;
+}
+
+roadMark::type_optional& roadMark::
+type ()
+{
+  return this->type_;
+}
+
+void roadMark::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void roadMark::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void roadMark::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const roadMark::userData_sequence& roadMark::
+userData () const
+{
+  return this->userData_;
+}
+
+roadMark::userData_sequence& roadMark::
+userData ()
+{
+  return this->userData_;
+}
+
+void roadMark::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const roadMark::include_sequence& roadMark::
+include () const
+{
+  return this->include_;
+}
+
+roadMark::include_sequence& roadMark::
+include ()
+{
+  return this->include_;
+}
+
+void roadMark::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const roadMark::sOffset_optional& roadMark::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+roadMark::sOffset_optional& roadMark::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void roadMark::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void roadMark::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const roadMark::type1_optional& roadMark::
+type1 () const
+{
+  return this->type1_;
+}
+
+roadMark::type1_optional& roadMark::
+type1 ()
+{
+  return this->type1_;
+}
+
+void roadMark::
+type1 (const type1_type& x)
+{
+  this->type1_.set (x);
+}
+
+void roadMark::
+type1 (const type1_optional& x)
+{
+  this->type1_ = x;
+}
+
+void roadMark::
+type1 (::std::unique_ptr< type1_type > x)
+{
+  this->type1_.set (std::move (x));
+}
+
+const roadMark::weight_optional& roadMark::
+weight () const
+{
+  return this->weight_;
+}
+
+roadMark::weight_optional& roadMark::
+weight ()
+{
+  return this->weight_;
+}
+
+void roadMark::
+weight (const weight_type& x)
+{
+  this->weight_.set (x);
+}
+
+void roadMark::
+weight (const weight_optional& x)
+{
+  this->weight_ = x;
+}
+
+void roadMark::
+weight (::std::unique_ptr< weight_type > x)
+{
+  this->weight_.set (std::move (x));
+}
+
+const roadMark::color_optional& roadMark::
+color () const
+{
+  return this->color_;
+}
+
+roadMark::color_optional& roadMark::
+color ()
+{
+  return this->color_;
+}
+
+void roadMark::
+color (const color_type& x)
+{
+  this->color_.set (x);
+}
+
+void roadMark::
+color (const color_optional& x)
+{
+  this->color_ = x;
+}
+
+void roadMark::
+color (::std::unique_ptr< color_type > x)
+{
+  this->color_.set (std::move (x));
+}
+
+const roadMark::material_optional& roadMark::
+material () const
+{
+  return this->material_;
+}
+
+roadMark::material_optional& roadMark::
+material ()
+{
+  return this->material_;
+}
+
+void roadMark::
+material (const material_type& x)
+{
+  this->material_.set (x);
+}
+
+void roadMark::
+material (const material_optional& x)
+{
+  this->material_ = x;
+}
+
+void roadMark::
+material (::std::unique_ptr< material_type > x)
+{
+  this->material_.set (std::move (x));
+}
+
+const roadMark::width_optional& roadMark::
+width () const
+{
+  return this->width_;
+}
+
+roadMark::width_optional& roadMark::
+width ()
+{
+  return this->width_;
+}
+
+void roadMark::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void roadMark::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+const roadMark::laneChange_optional& roadMark::
+laneChange () const
+{
+  return this->laneChange_;
+}
+
+roadMark::laneChange_optional& roadMark::
+laneChange ()
+{
+  return this->laneChange_;
+}
+
+void roadMark::
+laneChange (const laneChange_type& x)
+{
+  this->laneChange_.set (x);
+}
+
+void roadMark::
+laneChange (const laneChange_optional& x)
+{
+  this->laneChange_ = x;
+}
+
+void roadMark::
+laneChange (::std::unique_ptr< laneChange_type > x)
+{
+  this->laneChange_.set (std::move (x));
+}
+
+const roadMark::height_optional& roadMark::
+height () const
+{
+  return this->height_;
+}
+
+roadMark::height_optional& roadMark::
+height ()
+{
+  return this->height_;
+}
+
+void roadMark::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void roadMark::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+
+// material
+// 
+
+const material::userData_sequence& material::
+userData () const
+{
+  return this->userData_;
+}
+
+material::userData_sequence& material::
+userData ()
+{
+  return this->userData_;
+}
+
+void material::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const material::include_sequence& material::
+include () const
+{
+  return this->include_;
+}
+
+material::include_sequence& material::
+include ()
+{
+  return this->include_;
+}
+
+void material::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const material::sOffset_optional& material::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+material::sOffset_optional& material::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void material::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void material::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const material::surface_optional& material::
+surface () const
+{
+  return this->surface_;
+}
+
+material::surface_optional& material::
+surface ()
+{
+  return this->surface_;
+}
+
+void material::
+surface (const surface_type& x)
+{
+  this->surface_.set (x);
+}
+
+void material::
+surface (const surface_optional& x)
+{
+  this->surface_ = x;
+}
+
+void material::
+surface (::std::unique_ptr< surface_type > x)
+{
+  this->surface_.set (std::move (x));
+}
+
+const material::friction_optional& material::
+friction () const
+{
+  return this->friction_;
+}
+
+material::friction_optional& material::
+friction ()
+{
+  return this->friction_;
+}
+
+void material::
+friction (const friction_type& x)
+{
+  this->friction_.set (x);
+}
+
+void material::
+friction (const friction_optional& x)
+{
+  this->friction_ = x;
+}
+
+const material::roughness_optional& material::
+roughness () const
+{
+  return this->roughness_;
+}
+
+material::roughness_optional& material::
+roughness ()
+{
+  return this->roughness_;
+}
+
+void material::
+roughness (const roughness_type& x)
+{
+  this->roughness_.set (x);
+}
+
+void material::
+roughness (const roughness_optional& x)
+{
+  this->roughness_ = x;
+}
+
+
+// visibility
+// 
+
+const visibility::userData_sequence& visibility::
+userData () const
+{
+  return this->userData_;
+}
+
+visibility::userData_sequence& visibility::
+userData ()
+{
+  return this->userData_;
+}
+
+void visibility::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const visibility::include_sequence& visibility::
+include () const
+{
+  return this->include_;
+}
+
+visibility::include_sequence& visibility::
+include ()
+{
+  return this->include_;
+}
+
+void visibility::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const visibility::sOffset_optional& visibility::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+visibility::sOffset_optional& visibility::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void visibility::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void visibility::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const visibility::forward_optional& visibility::
+forward () const
+{
+  return this->forward_;
+}
+
+visibility::forward_optional& visibility::
+forward ()
+{
+  return this->forward_;
+}
+
+void visibility::
+forward (const forward_type& x)
+{
+  this->forward_.set (x);
+}
+
+void visibility::
+forward (const forward_optional& x)
+{
+  this->forward_ = x;
+}
+
+const visibility::back_optional& visibility::
+back () const
+{
+  return this->back_;
+}
+
+visibility::back_optional& visibility::
+back ()
+{
+  return this->back_;
+}
+
+void visibility::
+back (const back_type& x)
+{
+  this->back_.set (x);
+}
+
+void visibility::
+back (const back_optional& x)
+{
+  this->back_ = x;
+}
+
+const visibility::left_optional& visibility::
+left () const
+{
+  return this->left_;
+}
+
+visibility::left_optional& visibility::
+left ()
+{
+  return this->left_;
+}
+
+void visibility::
+left (const left_type& x)
+{
+  this->left_.set (x);
+}
+
+void visibility::
+left (const left_optional& x)
+{
+  this->left_ = x;
+}
+
+const visibility::right_optional& visibility::
+right () const
+{
+  return this->right_;
+}
+
+visibility::right_optional& visibility::
+right ()
+{
+  return this->right_;
+}
+
+void visibility::
+right (const right_type& x)
+{
+  this->right_.set (x);
+}
+
+void visibility::
+right (const right_optional& x)
+{
+  this->right_ = x;
+}
+
+
+// speed
+// 
+
+const speed::userData_sequence& speed::
+userData () const
+{
+  return this->userData_;
+}
+
+speed::userData_sequence& speed::
+userData ()
+{
+  return this->userData_;
+}
+
+void speed::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const speed::include_sequence& speed::
+include () const
+{
+  return this->include_;
+}
+
+speed::include_sequence& speed::
+include ()
+{
+  return this->include_;
+}
+
+void speed::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const speed::sOffset_optional& speed::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+speed::sOffset_optional& speed::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void speed::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void speed::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const speed::max_optional& speed::
+max () const
+{
+  return this->max_;
+}
+
+speed::max_optional& speed::
+max ()
+{
+  return this->max_;
+}
+
+void speed::
+max (const max_type& x)
+{
+  this->max_.set (x);
+}
+
+void speed::
+max (const max_optional& x)
+{
+  this->max_ = x;
+}
+
+const speed::unit_optional& speed::
+unit () const
+{
+  return this->unit_;
+}
+
+speed::unit_optional& speed::
+unit ()
+{
+  return this->unit_;
+}
+
+void speed::
+unit (const unit_type& x)
+{
+  this->unit_.set (x);
+}
+
+void speed::
+unit (const unit_optional& x)
+{
+  this->unit_ = x;
+}
+
+void speed::
+unit (::std::unique_ptr< unit_type > x)
+{
+  this->unit_.set (std::move (x));
+}
+
+
+// access1
+// 
+
+const access1::userData_sequence& access1::
+userData () const
+{
+  return this->userData_;
+}
+
+access1::userData_sequence& access1::
+userData ()
+{
+  return this->userData_;
+}
+
+void access1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const access1::include_sequence& access1::
+include () const
+{
+  return this->include_;
+}
+
+access1::include_sequence& access1::
+include ()
+{
+  return this->include_;
+}
+
+void access1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const access1::sOffset_optional& access1::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+access1::sOffset_optional& access1::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void access1::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void access1::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const access1::restriction_optional& access1::
+restriction () const
+{
+  return this->restriction_;
+}
+
+access1::restriction_optional& access1::
+restriction ()
+{
+  return this->restriction_;
+}
+
+void access1::
+restriction (const restriction_type& x)
+{
+  this->restriction_.set (x);
+}
+
+void access1::
+restriction (const restriction_optional& x)
+{
+  this->restriction_ = x;
+}
+
+void access1::
+restriction (::std::unique_ptr< restriction_type > x)
+{
+  this->restriction_.set (std::move (x));
+}
+
+
+// height
+// 
+
+const height::userData_sequence& height::
+userData () const
+{
+  return this->userData_;
+}
+
+height::userData_sequence& height::
+userData ()
+{
+  return this->userData_;
+}
+
+void height::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const height::include_sequence& height::
+include () const
+{
+  return this->include_;
+}
+
+height::include_sequence& height::
+include ()
+{
+  return this->include_;
+}
+
+void height::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const height::sOffset_optional& height::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+height::sOffset_optional& height::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void height::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void height::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const height::inner_optional& height::
+inner () const
+{
+  return this->inner_;
+}
+
+height::inner_optional& height::
+inner ()
+{
+  return this->inner_;
+}
+
+void height::
+inner (const inner_type& x)
+{
+  this->inner_.set (x);
+}
+
+void height::
+inner (const inner_optional& x)
+{
+  this->inner_ = x;
+}
+
+const height::outer_optional& height::
+outer () const
+{
+  return this->outer_;
+}
+
+height::outer_optional& height::
+outer ()
+{
+  return this->outer_;
+}
+
+void height::
+outer (const outer_type& x)
+{
+  this->outer_.set (x);
+}
+
+void height::
+outer (const outer_optional& x)
+{
+  this->outer_ = x;
+}
+
+
+// rule1
+// 
+
+const rule1::userData_sequence& rule1::
+userData () const
+{
+  return this->userData_;
+}
+
+rule1::userData_sequence& rule1::
+userData ()
+{
+  return this->userData_;
+}
+
+void rule1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const rule1::include_sequence& rule1::
+include () const
+{
+  return this->include_;
+}
+
+rule1::include_sequence& rule1::
+include ()
+{
+  return this->include_;
+}
+
+void rule1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const rule1::sOffset_optional& rule1::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+rule1::sOffset_optional& rule1::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void rule1::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void rule1::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const rule1::value_optional& rule1::
+value () const
+{
+  return this->value_;
+}
+
+rule1::value_optional& rule1::
+value ()
+{
+  return this->value_;
+}
+
+void rule1::
+value (const value_type& x)
+{
+  this->value_.set (x);
+}
+
+void rule1::
+value (const value_optional& x)
+{
+  this->value_ = x;
+}
+
+void rule1::
+value (::std::unique_ptr< value_type > x)
+{
+  this->value_.set (std::move (x));
+}
+
+
+// link1
+// 
+
+const link1::predecessor_optional& link1::
+predecessor () const
+{
+  return this->predecessor_;
+}
+
+link1::predecessor_optional& link1::
+predecessor ()
+{
+  return this->predecessor_;
+}
+
+void link1::
+predecessor (const predecessor_type& x)
+{
+  this->predecessor_.set (x);
+}
+
+void link1::
+predecessor (const predecessor_optional& x)
+{
+  this->predecessor_ = x;
+}
+
+void link1::
+predecessor (::std::unique_ptr< predecessor_type > x)
+{
+  this->predecessor_.set (std::move (x));
+}
+
+const link1::successor_optional& link1::
+successor () const
+{
+  return this->successor_;
+}
+
+link1::successor_optional& link1::
+successor ()
+{
+  return this->successor_;
+}
+
+void link1::
+successor (const successor_type& x)
+{
+  this->successor_.set (x);
+}
+
+void link1::
+successor (const successor_optional& x)
+{
+  this->successor_ = x;
+}
+
+void link1::
+successor (::std::unique_ptr< successor_type > x)
+{
+  this->successor_.set (std::move (x));
+}
+
+const link1::userData_sequence& link1::
+userData () const
+{
+  return this->userData_;
+}
+
+link1::userData_sequence& link1::
+userData ()
+{
+  return this->userData_;
+}
+
+void link1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const link1::include_sequence& link1::
+include () const
+{
+  return this->include_;
+}
+
+link1::include_sequence& link1::
+include ()
+{
+  return this->include_;
+}
+
+void link1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// roadMark1
+// 
+
+const roadMark1::type_optional& roadMark1::
+type () const
+{
+  return this->type_;
+}
+
+roadMark1::type_optional& roadMark1::
+type ()
+{
+  return this->type_;
+}
+
+void roadMark1::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void roadMark1::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void roadMark1::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const roadMark1::userData_sequence& roadMark1::
+userData () const
+{
+  return this->userData_;
+}
+
+roadMark1::userData_sequence& roadMark1::
+userData ()
+{
+  return this->userData_;
+}
+
+void roadMark1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const roadMark1::include_sequence& roadMark1::
+include () const
+{
+  return this->include_;
+}
+
+roadMark1::include_sequence& roadMark1::
+include ()
+{
+  return this->include_;
+}
+
+void roadMark1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const roadMark1::sOffset_optional& roadMark1::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+roadMark1::sOffset_optional& roadMark1::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void roadMark1::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void roadMark1::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const roadMark1::type1_optional& roadMark1::
+type1 () const
+{
+  return this->type1_;
+}
+
+roadMark1::type1_optional& roadMark1::
+type1 ()
+{
+  return this->type1_;
+}
+
+void roadMark1::
+type1 (const type1_type& x)
+{
+  this->type1_.set (x);
+}
+
+void roadMark1::
+type1 (const type1_optional& x)
+{
+  this->type1_ = x;
+}
+
+void roadMark1::
+type1 (::std::unique_ptr< type1_type > x)
+{
+  this->type1_.set (std::move (x));
+}
+
+const roadMark1::weight_optional& roadMark1::
+weight () const
+{
+  return this->weight_;
+}
+
+roadMark1::weight_optional& roadMark1::
+weight ()
+{
+  return this->weight_;
+}
+
+void roadMark1::
+weight (const weight_type& x)
+{
+  this->weight_.set (x);
+}
+
+void roadMark1::
+weight (const weight_optional& x)
+{
+  this->weight_ = x;
+}
+
+void roadMark1::
+weight (::std::unique_ptr< weight_type > x)
+{
+  this->weight_.set (std::move (x));
+}
+
+const roadMark1::color_optional& roadMark1::
+color () const
+{
+  return this->color_;
+}
+
+roadMark1::color_optional& roadMark1::
+color ()
+{
+  return this->color_;
+}
+
+void roadMark1::
+color (const color_type& x)
+{
+  this->color_.set (x);
+}
+
+void roadMark1::
+color (const color_optional& x)
+{
+  this->color_ = x;
+}
+
+void roadMark1::
+color (::std::unique_ptr< color_type > x)
+{
+  this->color_.set (std::move (x));
+}
+
+const roadMark1::material_optional& roadMark1::
+material () const
+{
+  return this->material_;
+}
+
+roadMark1::material_optional& roadMark1::
+material ()
+{
+  return this->material_;
+}
+
+void roadMark1::
+material (const material_type& x)
+{
+  this->material_.set (x);
+}
+
+void roadMark1::
+material (const material_optional& x)
+{
+  this->material_ = x;
+}
+
+void roadMark1::
+material (::std::unique_ptr< material_type > x)
+{
+  this->material_.set (std::move (x));
+}
+
+const roadMark1::width_optional& roadMark1::
+width () const
+{
+  return this->width_;
+}
+
+roadMark1::width_optional& roadMark1::
+width ()
+{
+  return this->width_;
+}
+
+void roadMark1::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void roadMark1::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+const roadMark1::laneChange_optional& roadMark1::
+laneChange () const
+{
+  return this->laneChange_;
+}
+
+roadMark1::laneChange_optional& roadMark1::
+laneChange ()
+{
+  return this->laneChange_;
+}
+
+void roadMark1::
+laneChange (const laneChange_type& x)
+{
+  this->laneChange_.set (x);
+}
+
+void roadMark1::
+laneChange (const laneChange_optional& x)
+{
+  this->laneChange_ = x;
+}
+
+void roadMark1::
+laneChange (::std::unique_ptr< laneChange_type > x)
+{
+  this->laneChange_.set (std::move (x));
+}
+
+const roadMark1::height_optional& roadMark1::
+height () const
+{
+  return this->height_;
+}
+
+roadMark1::height_optional& roadMark1::
+height ()
+{
+  return this->height_;
+}
+
+void roadMark1::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void roadMark1::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+
+// header
+// 
+
+const header::geoReference_optional& header::
+geoReference () const
+{
+  return this->geoReference_;
+}
+
+header::geoReference_optional& header::
+geoReference ()
+{
+  return this->geoReference_;
+}
+
+void header::
+geoReference (const geoReference_type& x)
+{
+  this->geoReference_.set (x);
+}
+
+void header::
+geoReference (const geoReference_optional& x)
+{
+  this->geoReference_ = x;
+}
+
+void header::
+geoReference (::std::unique_ptr< geoReference_type > x)
+{
+  this->geoReference_.set (std::move (x));
+}
+
+const header::userData_sequence& header::
+userData () const
+{
+  return this->userData_;
+}
+
+header::userData_sequence& header::
+userData ()
+{
+  return this->userData_;
+}
+
+void header::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const header::include_sequence& header::
+include () const
+{
+  return this->include_;
+}
+
+header::include_sequence& header::
+include ()
+{
+  return this->include_;
+}
+
+void header::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const header::revMajor_optional& header::
+revMajor () const
+{
+  return this->revMajor_;
+}
+
+header::revMajor_optional& header::
+revMajor ()
+{
+  return this->revMajor_;
+}
+
+void header::
+revMajor (const revMajor_type& x)
+{
+  this->revMajor_.set (x);
+}
+
+void header::
+revMajor (const revMajor_optional& x)
+{
+  this->revMajor_ = x;
+}
+
+const header::revMinor_optional& header::
+revMinor () const
+{
+  return this->revMinor_;
+}
+
+header::revMinor_optional& header::
+revMinor ()
+{
+  return this->revMinor_;
+}
+
+void header::
+revMinor (const revMinor_type& x)
+{
+  this->revMinor_.set (x);
+}
+
+void header::
+revMinor (const revMinor_optional& x)
+{
+  this->revMinor_ = x;
+}
+
+const header::name_optional& header::
+name () const
+{
+  return this->name_;
+}
+
+header::name_optional& header::
+name ()
+{
+  return this->name_;
+}
+
+void header::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void header::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void header::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const header::version_optional& header::
+version () const
+{
+  return this->version_;
+}
+
+header::version_optional& header::
+version ()
+{
+  return this->version_;
+}
+
+void header::
+version (const version_type& x)
+{
+  this->version_.set (x);
+}
+
+void header::
+version (const version_optional& x)
+{
+  this->version_ = x;
+}
+
+const header::date_optional& header::
+date () const
+{
+  return this->date_;
+}
+
+header::date_optional& header::
+date ()
+{
+  return this->date_;
+}
+
+void header::
+date (const date_type& x)
+{
+  this->date_.set (x);
+}
+
+void header::
+date (const date_optional& x)
+{
+  this->date_ = x;
+}
+
+void header::
+date (::std::unique_ptr< date_type > x)
+{
+  this->date_.set (std::move (x));
+}
+
+const header::north_optional& header::
+north () const
+{
+  return this->north_;
+}
+
+header::north_optional& header::
+north ()
+{
+  return this->north_;
+}
+
+void header::
+north (const north_type& x)
+{
+  this->north_.set (x);
+}
+
+void header::
+north (const north_optional& x)
+{
+  this->north_ = x;
+}
+
+const header::south_optional& header::
+south () const
+{
+  return this->south_;
+}
+
+header::south_optional& header::
+south ()
+{
+  return this->south_;
+}
+
+void header::
+south (const south_type& x)
+{
+  this->south_.set (x);
+}
+
+void header::
+south (const south_optional& x)
+{
+  this->south_ = x;
+}
+
+const header::east_optional& header::
+east () const
+{
+  return this->east_;
+}
+
+header::east_optional& header::
+east ()
+{
+  return this->east_;
+}
+
+void header::
+east (const east_type& x)
+{
+  this->east_.set (x);
+}
+
+void header::
+east (const east_optional& x)
+{
+  this->east_ = x;
+}
+
+const header::west_optional& header::
+west () const
+{
+  return this->west_;
+}
+
+header::west_optional& header::
+west ()
+{
+  return this->west_;
+}
+
+void header::
+west (const west_type& x)
+{
+  this->west_.set (x);
+}
+
+void header::
+west (const west_optional& x)
+{
+  this->west_ = x;
+}
+
+const header::vendor_optional& header::
+vendor () const
+{
+  return this->vendor_;
+}
+
+header::vendor_optional& header::
+vendor ()
+{
+  return this->vendor_;
+}
+
+void header::
+vendor (const vendor_type& x)
+{
+  this->vendor_.set (x);
+}
+
+void header::
+vendor (const vendor_optional& x)
+{
+  this->vendor_ = x;
+}
+
+void header::
+vendor (::std::unique_ptr< vendor_type > x)
+{
+  this->vendor_.set (std::move (x));
+}
+
+
+// road
+// 
+
+const road::link_optional& road::
+lane_link () const
+{
+  return this->lane_link_;
+}
+
+road::link_optional& road::
+lane_link ()
+{
+  return this->lane_link_;
+}
+
+void road::
+lane_link (const link_type& x)
+{
+  this->lane_link_.set (x);
+}
+
+void road::
+lane_link (const link_optional& x)
+{
+  this->lane_link_ = x;
+}
+
+void road::
+lane_link (::std::unique_ptr< link_type > x)
+{
+  this->lane_link_.set (std::move (x));
+}
+
+const road::type_sequence& road::
+type () const
+{
+  return this->type_;
+}
+
+road::type_sequence& road::
+type ()
+{
+  return this->type_;
+}
+
+void road::
+type (const type_sequence& s)
+{
+  this->type_ = s;
+}
+
+const road::planView_type& road::
+planView () const
+{
+  return this->planView_.get ();
+}
+
+road::planView_type& road::
+planView ()
+{
+  return this->planView_.get ();
+}
+
+void road::
+planView (const planView_type& x)
+{
+  this->planView_.set (x);
+}
+
+void road::
+planView (::std::unique_ptr< planView_type > x)
+{
+  this->planView_.set (std::move (x));
+}
+
+const road::elevationProfile_optional& road::
+elevationProfile () const
+{
+  return this->elevationProfile_;
+}
+
+road::elevationProfile_optional& road::
+elevationProfile ()
+{
+  return this->elevationProfile_;
+}
+
+void road::
+elevationProfile (const elevationProfile_type& x)
+{
+  this->elevationProfile_.set (x);
+}
+
+void road::
+elevationProfile (const elevationProfile_optional& x)
+{
+  this->elevationProfile_ = x;
+}
+
+void road::
+elevationProfile (::std::unique_ptr< elevationProfile_type > x)
+{
+  this->elevationProfile_.set (std::move (x));
+}
+
+const road::lateralProfile_optional& road::
+lateralProfile () const
+{
+  return this->lateralProfile_;
+}
+
+road::lateralProfile_optional& road::
+lateralProfile ()
+{
+  return this->lateralProfile_;
+}
+
+void road::
+lateralProfile (const lateralProfile_type& x)
+{
+  this->lateralProfile_.set (x);
+}
+
+void road::
+lateralProfile (const lateralProfile_optional& x)
+{
+  this->lateralProfile_ = x;
+}
+
+void road::
+lateralProfile (::std::unique_ptr< lateralProfile_type > x)
+{
+  this->lateralProfile_.set (std::move (x));
+}
+
+const road::lanes_type& road::
+lanes () const
+{
+  return this->lanes_.get ();
+}
+
+road::lanes_type& road::
+lanes ()
+{
+  return this->lanes_.get ();
+}
+
+void road::
+lanes (const lanes_type& x)
+{
+  this->lanes_.set (x);
+}
+
+void road::
+lanes (::std::unique_ptr< lanes_type > x)
+{
+  this->lanes_.set (std::move (x));
+}
+
+const road::objects_optional& road::
+objects () const
+{
+  return this->objects_;
+}
+
+road::objects_optional& road::
+objects ()
+{
+  return this->objects_;
+}
+
+void road::
+objects (const objects_type& x)
+{
+  this->objects_.set (x);
+}
+
+void road::
+objects (const objects_optional& x)
+{
+  this->objects_ = x;
+}
+
+void road::
+objects (::std::unique_ptr< objects_type > x)
+{
+  this->objects_.set (std::move (x));
+}
+
+const road::signals_optional& road::
+signals () const
+{
+  return this->signals_;
+}
+
+road::signals_optional& road::
+signals ()
+{
+  return this->signals_;
+}
+
+void road::
+signals (const signals_type& x)
+{
+  this->signals_.set (x);
+}
+
+void road::
+signals (const signals_optional& x)
+{
+  this->signals_ = x;
+}
+
+void road::
+signals (::std::unique_ptr< signals_type > x)
+{
+  this->signals_.set (std::move (x));
+}
+
+const road::surface_optional& road::
+surface () const
+{
+  return this->surface_;
+}
+
+road::surface_optional& road::
+surface ()
+{
+  return this->surface_;
+}
+
+void road::
+surface (const surface_type& x)
+{
+  this->surface_.set (x);
+}
+
+void road::
+surface (const surface_optional& x)
+{
+  this->surface_ = x;
+}
+
+void road::
+surface (::std::unique_ptr< surface_type > x)
+{
+  this->surface_.set (std::move (x));
+}
+
+const road::railroad_optional& road::
+railroad () const
+{
+  return this->railroad_;
+}
+
+road::railroad_optional& road::
+railroad ()
+{
+  return this->railroad_;
+}
+
+void road::
+railroad (const railroad_type& x)
+{
+  this->railroad_.set (x);
+}
+
+void road::
+railroad (const railroad_optional& x)
+{
+  this->railroad_ = x;
+}
+
+void road::
+railroad (::std::unique_ptr< railroad_type > x)
+{
+  this->railroad_.set (std::move (x));
+}
+
+const road::userData_sequence& road::
+userData () const
+{
+  return this->userData_;
+}
+
+road::userData_sequence& road::
+userData ()
+{
+  return this->userData_;
+}
+
+void road::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const road::include_sequence& road::
+include () const
+{
+  return this->include_;
+}
+
+road::include_sequence& road::
+include ()
+{
+  return this->include_;
+}
+
+void road::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const road::name_optional& road::
+name () const
+{
+  return this->name_;
+}
+
+road::name_optional& road::
+name ()
+{
+  return this->name_;
+}
+
+void road::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void road::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void road::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const road::length_optional& road::
+length () const
+{
+  return this->length_;
+}
+
+road::length_optional& road::
+length ()
+{
+  return this->length_;
+}
+
+void road::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void road::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const road::id_optional& road::
+id () const
+{
+  return this->id_;
+}
+
+road::id_optional& road::
+id ()
+{
+  return this->id_;
+}
+
+void road::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void road::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void road::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const road::junction_optional& road::
+junction () const
+{
+  return this->junction_;
+}
+
+road::junction_optional& road::
+junction ()
+{
+  return this->junction_;
+}
+
+void road::
+junction (const junction_type& x)
+{
+  this->junction_.set (x);
+}
+
+void road::
+junction (const junction_optional& x)
+{
+  this->junction_ = x;
+}
+
+void road::
+junction (::std::unique_ptr< junction_type > x)
+{
+  this->junction_.set (std::move (x));
+}
+
+
+// controller
+// 
+
+const controller::control_sequence& controller::
+control () const
+{
+  return this->control_;
+}
+
+controller::control_sequence& controller::
+control ()
+{
+  return this->control_;
+}
+
+void controller::
+control (const control_sequence& s)
+{
+  this->control_ = s;
+}
+
+const controller::userData_sequence& controller::
+userData () const
+{
+  return this->userData_;
+}
+
+controller::userData_sequence& controller::
+userData ()
+{
+  return this->userData_;
+}
+
+void controller::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const controller::include_sequence& controller::
+include () const
+{
+  return this->include_;
+}
+
+controller::include_sequence& controller::
+include ()
+{
+  return this->include_;
+}
+
+void controller::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const controller::id_optional& controller::
+id () const
+{
+  return this->id_;
+}
+
+controller::id_optional& controller::
+id ()
+{
+  return this->id_;
+}
+
+void controller::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void controller::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void controller::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const controller::name_optional& controller::
+name () const
+{
+  return this->name_;
+}
+
+controller::name_optional& controller::
+name ()
+{
+  return this->name_;
+}
+
+void controller::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void controller::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void controller::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const controller::sequence_optional& controller::
+sequence () const
+{
+  return this->sequence_;
+}
+
+controller::sequence_optional& controller::
+sequence ()
+{
+  return this->sequence_;
+}
+
+void controller::
+sequence (const sequence_type& x)
+{
+  this->sequence_.set (x);
+}
+
+void controller::
+sequence (const sequence_optional& x)
+{
+  this->sequence_ = x;
+}
+
+
+// junction
+// 
+
+const junction::connection_sequence& junction::
+connection () const
+{
+  return this->connection_;
+}
+
+junction::connection_sequence& junction::
+connection ()
+{
+  return this->connection_;
+}
+
+void junction::
+connection (const connection_sequence& s)
+{
+  this->connection_ = s;
+}
+
+const junction::priority_sequence& junction::
+priority () const
+{
+  return this->priority_;
+}
+
+junction::priority_sequence& junction::
+priority ()
+{
+  return this->priority_;
+}
+
+void junction::
+priority (const priority_sequence& s)
+{
+  this->priority_ = s;
+}
+
+const junction::controller_sequence& junction::
+controller () const
+{
+  return this->controller_;
+}
+
+junction::controller_sequence& junction::
+controller ()
+{
+  return this->controller_;
+}
+
+void junction::
+controller (const controller_sequence& s)
+{
+  this->controller_ = s;
+}
+
+const junction::userData_sequence& junction::
+userData () const
+{
+  return this->userData_;
+}
+
+junction::userData_sequence& junction::
+userData ()
+{
+  return this->userData_;
+}
+
+void junction::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const junction::include_sequence& junction::
+include () const
+{
+  return this->include_;
+}
+
+junction::include_sequence& junction::
+include ()
+{
+  return this->include_;
+}
+
+void junction::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const junction::name_optional& junction::
+name () const
+{
+  return this->name_;
+}
+
+junction::name_optional& junction::
+name ()
+{
+  return this->name_;
+}
+
+void junction::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void junction::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void junction::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const junction::id_optional& junction::
+id () const
+{
+  return this->id_;
+}
+
+junction::id_optional& junction::
+id ()
+{
+  return this->id_;
+}
+
+void junction::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void junction::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void junction::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+
+// junctionGroup
+// 
+
+const junctionGroup::junctionReference_sequence& junctionGroup::
+junctionReference () const
+{
+  return this->junctionReference_;
+}
+
+junctionGroup::junctionReference_sequence& junctionGroup::
+junctionReference ()
+{
+  return this->junctionReference_;
+}
+
+void junctionGroup::
+junctionReference (const junctionReference_sequence& s)
+{
+  this->junctionReference_ = s;
+}
+
+const junctionGroup::userData_sequence& junctionGroup::
+userData () const
+{
+  return this->userData_;
+}
+
+junctionGroup::userData_sequence& junctionGroup::
+userData ()
+{
+  return this->userData_;
+}
+
+void junctionGroup::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const junctionGroup::include_sequence& junctionGroup::
+include () const
+{
+  return this->include_;
+}
+
+junctionGroup::include_sequence& junctionGroup::
+include ()
+{
+  return this->include_;
+}
+
+void junctionGroup::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const junctionGroup::name_optional& junctionGroup::
+name () const
+{
+  return this->name_;
+}
+
+junctionGroup::name_optional& junctionGroup::
+name ()
+{
+  return this->name_;
+}
+
+void junctionGroup::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void junctionGroup::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void junctionGroup::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const junctionGroup::id_optional& junctionGroup::
+id () const
+{
+  return this->id_;
+}
+
+junctionGroup::id_optional& junctionGroup::
+id ()
+{
+  return this->id_;
+}
+
+void junctionGroup::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void junctionGroup::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void junctionGroup::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const junctionGroup::type_optional& junctionGroup::
+type () const
+{
+  return this->type_;
+}
+
+junctionGroup::type_optional& junctionGroup::
+type ()
+{
+  return this->type_;
+}
+
+void junctionGroup::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void junctionGroup::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void junctionGroup::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// station
+// 
+
+const station::platform_sequence& station::
+platform () const
+{
+  return this->platform_;
+}
+
+station::platform_sequence& station::
+platform ()
+{
+  return this->platform_;
+}
+
+void station::
+platform (const platform_sequence& s)
+{
+  this->platform_ = s;
+}
+
+const station::userData_sequence& station::
+userData () const
+{
+  return this->userData_;
+}
+
+station::userData_sequence& station::
+userData ()
+{
+  return this->userData_;
+}
+
+void station::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const station::include_sequence& station::
+include () const
+{
+  return this->include_;
+}
+
+station::include_sequence& station::
+include ()
+{
+  return this->include_;
+}
+
+void station::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const station::name_optional& station::
+name () const
+{
+  return this->name_;
+}
+
+station::name_optional& station::
+name ()
+{
+  return this->name_;
+}
+
+void station::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void station::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void station::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const station::id_optional& station::
+id () const
+{
+  return this->id_;
+}
+
+station::id_optional& station::
+id ()
+{
+  return this->id_;
+}
+
+void station::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void station::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void station::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const station::type_optional& station::
+type () const
+{
+  return this->type_;
+}
+
+station::type_optional& station::
+type ()
+{
+  return this->type_;
+}
+
+void station::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void station::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void station::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// predecessor
+// 
+
+const predecessor::id_optional& predecessor::
+id () const
+{
+  return this->id_;
+}
+
+predecessor::id_optional& predecessor::
+id ()
+{
+  return this->id_;
+}
+
+void predecessor::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void predecessor::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+
+// successor
+// 
+
+const successor::id_optional& successor::
+id () const
+{
+  return this->id_;
+}
+
+successor::id_optional& successor::
+id ()
+{
+  return this->id_;
+}
+
+void successor::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void successor::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+
+// type
+// 
+
+const type::line_sequence& type::
+line () const
+{
+  return this->line_;
+}
+
+type::line_sequence& type::
+line ()
+{
+  return this->line_;
+}
+
+void type::
+line (const line_sequence& s)
+{
+  this->line_ = s;
+}
+
+const type::name_optional& type::
+name () const
+{
+  return this->name_;
+}
+
+type::name_optional& type::
+name ()
+{
+  return this->name_;
+}
+
+void type::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void type::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void type::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const type::width_optional& type::
+width () const
+{
+  return this->width_;
+}
+
+type::width_optional& type::
+width ()
+{
+  return this->width_;
+}
+
+void type::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void type::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+
+// type1
+// 
+
+const type1::line_sequence& type1::
+line () const
+{
+  return this->line_;
+}
+
+type1::line_sequence& type1::
+line ()
+{
+  return this->line_;
+}
+
+void type1::
+line (const line_sequence& s)
+{
+  this->line_ = s;
+}
+
+const type1::name_optional& type1::
+name () const
+{
+  return this->name_;
+}
+
+type1::name_optional& type1::
+name ()
+{
+  return this->name_;
+}
+
+void type1::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void type1::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void type1::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const type1::width_optional& type1::
+width () const
+{
+  return this->width_;
+}
+
+type1::width_optional& type1::
+width ()
+{
+  return this->width_;
+}
+
+void type1::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void type1::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+
+// link2
+// 
+
+const link2::predecessor_optional& link2::
+predecessor () const
+{
+  return this->predecessor_;
+}
+
+link2::predecessor_optional& link2::
+predecessor ()
+{
+  return this->predecessor_;
+}
+
+void link2::
+predecessor (const predecessor_type& x)
+{
+  this->predecessor_.set (x);
+}
+
+void link2::
+predecessor (const predecessor_optional& x)
+{
+  this->predecessor_ = x;
+}
+
+void link2::
+predecessor (::std::unique_ptr< predecessor_type > x)
+{
+  this->predecessor_.set (std::move (x));
+}
+
+const link2::successor_optional& link2::
+successor () const
+{
+  return this->successor_;
+}
+
+link2::successor_optional& link2::
+successor ()
+{
+  return this->successor_;
+}
+
+void link2::
+successor (const successor_type& x)
+{
+  this->successor_.set (x);
+}
+
+void link2::
+successor (const successor_optional& x)
+{
+  this->successor_ = x;
+}
+
+void link2::
+successor (::std::unique_ptr< successor_type > x)
+{
+  this->successor_.set (std::move (x));
+}
+
+const link2::neighbor_sequence& link2::
+neighbor () const
+{
+  return this->neighbor_;
+}
+
+link2::neighbor_sequence& link2::
+neighbor ()
+{
+  return this->neighbor_;
+}
+
+void link2::
+neighbor (const neighbor_sequence& s)
+{
+  this->neighbor_ = s;
+}
+
+const link2::userData_sequence& link2::
+userData () const
+{
+  return this->userData_;
+}
+
+link2::userData_sequence& link2::
+userData ()
+{
+  return this->userData_;
+}
+
+void link2::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const link2::include_sequence& link2::
+include () const
+{
+  return this->include_;
+}
+
+link2::include_sequence& link2::
+include ()
+{
+  return this->include_;
+}
+
+void link2::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// type2
+// 
+
+const type2::speed_optional& type2::
+speed () const
+{
+  return this->speed_;
+}
+
+type2::speed_optional& type2::
+speed ()
+{
+  return this->speed_;
+}
+
+void type2::
+speed (const speed_type& x)
+{
+  this->speed_.set (x);
+}
+
+void type2::
+speed (const speed_optional& x)
+{
+  this->speed_ = x;
+}
+
+void type2::
+speed (::std::unique_ptr< speed_type > x)
+{
+  this->speed_.set (std::move (x));
+}
+
+const type2::userData_sequence& type2::
+userData () const
+{
+  return this->userData_;
+}
+
+type2::userData_sequence& type2::
+userData ()
+{
+  return this->userData_;
+}
+
+void type2::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const type2::include_sequence& type2::
+include () const
+{
+  return this->include_;
+}
+
+type2::include_sequence& type2::
+include ()
+{
+  return this->include_;
+}
+
+void type2::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const type2::s_optional& type2::
+s () const
+{
+  return this->s_;
+}
+
+type2::s_optional& type2::
+s ()
+{
+  return this->s_;
+}
+
+void type2::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void type2::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const type2::type_optional& type2::
+type () const
+{
+  return this->type_;
+}
+
+type2::type_optional& type2::
+type ()
+{
+  return this->type_;
+}
+
+void type2::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void type2::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void type2::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// planView
+// 
+
+const planView::geometry_sequence& planView::
+geometry () const
+{
+  return this->geometry_;
+}
+
+planView::geometry_sequence& planView::
+geometry ()
+{
+  return this->geometry_;
+}
+
+void planView::
+geometry (const geometry_sequence& s)
+{
+  this->geometry_ = s;
+}
+
+
+// elevationProfile
+// 
+
+const elevationProfile::elevation_sequence& elevationProfile::
+elevation () const
+{
+  return this->elevation_;
+}
+
+elevationProfile::elevation_sequence& elevationProfile::
+elevation ()
+{
+  return this->elevation_;
+}
+
+void elevationProfile::
+elevation (const elevation_sequence& s)
+{
+  this->elevation_ = s;
+}
+
+const elevationProfile::userData_sequence& elevationProfile::
+userData () const
+{
+  return this->userData_;
+}
+
+elevationProfile::userData_sequence& elevationProfile::
+userData ()
+{
+  return this->userData_;
+}
+
+void elevationProfile::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const elevationProfile::include_sequence& elevationProfile::
+include () const
+{
+  return this->include_;
+}
+
+elevationProfile::include_sequence& elevationProfile::
+include ()
+{
+  return this->include_;
+}
+
+void elevationProfile::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// lateralProfile
+// 
+
+const lateralProfile::superelevation_sequence& lateralProfile::
+superelevation () const
+{
+  return this->superelevation_;
+}
+
+lateralProfile::superelevation_sequence& lateralProfile::
+superelevation ()
+{
+  return this->superelevation_;
+}
+
+void lateralProfile::
+superelevation (const superelevation_sequence& s)
+{
+  this->superelevation_ = s;
+}
+
+const lateralProfile::crossfall_sequence& lateralProfile::
+crossfall () const
+{
+  return this->crossfall_;
+}
+
+lateralProfile::crossfall_sequence& lateralProfile::
+crossfall ()
+{
+  return this->crossfall_;
+}
+
+void lateralProfile::
+crossfall (const crossfall_sequence& s)
+{
+  this->crossfall_ = s;
+}
+
+const lateralProfile::shape_sequence& lateralProfile::
+shape () const
+{
+  return this->shape_;
+}
+
+lateralProfile::shape_sequence& lateralProfile::
+shape ()
+{
+  return this->shape_;
+}
+
+void lateralProfile::
+shape (const shape_sequence& s)
+{
+  this->shape_ = s;
+}
+
+const lateralProfile::userData_sequence& lateralProfile::
+userData () const
+{
+  return this->userData_;
+}
+
+lateralProfile::userData_sequence& lateralProfile::
+userData ()
+{
+  return this->userData_;
+}
+
+void lateralProfile::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const lateralProfile::include_sequence& lateralProfile::
+include () const
+{
+  return this->include_;
+}
+
+lateralProfile::include_sequence& lateralProfile::
+include ()
+{
+  return this->include_;
+}
+
+void lateralProfile::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// lanes
+// 
+
+const lanes::laneOffset_sequence& lanes::
+laneOffset () const
+{
+  return this->laneOffset_;
+}
+
+lanes::laneOffset_sequence& lanes::
+laneOffset ()
+{
+  return this->laneOffset_;
+}
+
+void lanes::
+laneOffset (const laneOffset_sequence& s)
+{
+  this->laneOffset_ = s;
+}
+
+const lanes::laneSection_sequence& lanes::
+laneSection () const
+{
+  return this->laneSection_;
+}
+
+lanes::laneSection_sequence& lanes::
+laneSection ()
+{
+  return this->laneSection_;
+}
+
+void lanes::
+laneSection (const laneSection_sequence& s)
+{
+  this->laneSection_ = s;
+}
+
+
+// objects
+// 
+
+const objects::object_sequence& objects::
+object () const
+{
+  return this->object_;
+}
+
+objects::object_sequence& objects::
+object ()
+{
+  return this->object_;
+}
+
+void objects::
+object (const object_sequence& s)
+{
+  this->object_ = s;
+}
+
+const objects::objectReference_sequence& objects::
+objectReference () const
+{
+  return this->objectReference_;
+}
+
+objects::objectReference_sequence& objects::
+objectReference ()
+{
+  return this->objectReference_;
+}
+
+void objects::
+objectReference (const objectReference_sequence& s)
+{
+  this->objectReference_ = s;
+}
+
+const objects::tunnel_sequence& objects::
+tunnel () const
+{
+  return this->tunnel_;
+}
+
+objects::tunnel_sequence& objects::
+tunnel ()
+{
+  return this->tunnel_;
+}
+
+void objects::
+tunnel (const tunnel_sequence& s)
+{
+  this->tunnel_ = s;
+}
+
+const objects::bridge_sequence& objects::
+bridge () const
+{
+  return this->bridge_;
+}
+
+objects::bridge_sequence& objects::
+bridge ()
+{
+  return this->bridge_;
+}
+
+void objects::
+bridge (const bridge_sequence& s)
+{
+  this->bridge_ = s;
+}
+
+const objects::userData_sequence& objects::
+userData () const
+{
+  return this->userData_;
+}
+
+objects::userData_sequence& objects::
+userData ()
+{
+  return this->userData_;
+}
+
+void objects::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const objects::include_sequence& objects::
+include () const
+{
+  return this->include_;
+}
+
+objects::include_sequence& objects::
+include ()
+{
+  return this->include_;
+}
+
+void objects::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// signals
+// 
+
+const signals::signal_sequence& signals::
+signal () const
+{
+  return this->signal_;
+}
+
+signals::signal_sequence& signals::
+signal ()
+{
+  return this->signal_;
+}
+
+void signals::
+signal (const signal_sequence& s)
+{
+  this->signal_ = s;
+}
+
+const signals::signalReference_sequence& signals::
+signalReference () const
+{
+  return this->signalReference_;
+}
+
+signals::signalReference_sequence& signals::
+signalReference ()
+{
+  return this->signalReference_;
+}
+
+void signals::
+signalReference (const signalReference_sequence& s)
+{
+  this->signalReference_ = s;
+}
+
+const signals::userData_sequence& signals::
+userData () const
+{
+  return this->userData_;
+}
+
+signals::userData_sequence& signals::
+userData ()
+{
+  return this->userData_;
+}
+
+void signals::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const signals::include_sequence& signals::
+include () const
+{
+  return this->include_;
+}
+
+signals::include_sequence& signals::
+include ()
+{
+  return this->include_;
+}
+
+void signals::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// surface
+// 
+
+const surface::CRG_sequence& surface::
+CRG () const
+{
+  return this->CRG_;
+}
+
+surface::CRG_sequence& surface::
+CRG ()
+{
+  return this->CRG_;
+}
+
+void surface::
+CRG (const CRG_sequence& s)
+{
+  this->CRG_ = s;
+}
+
+const surface::userData_sequence& surface::
+userData () const
+{
+  return this->userData_;
+}
+
+surface::userData_sequence& surface::
+userData ()
+{
+  return this->userData_;
+}
+
+void surface::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const surface::include_sequence& surface::
+include () const
+{
+  return this->include_;
+}
+
+surface::include_sequence& surface::
+include ()
+{
+  return this->include_;
+}
+
+void surface::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// railroad
+// 
+
+const railroad::switch_sequence& railroad::
+switch_ () const
+{
+  return this->switch__;
+}
+
+railroad::switch_sequence& railroad::
+switch_ ()
+{
+  return this->switch__;
+}
+
+void railroad::
+switch_ (const switch_sequence& s)
+{
+  this->switch__ = s;
+}
+
+const railroad::userData_sequence& railroad::
+userData () const
+{
+  return this->userData_;
+}
+
+railroad::userData_sequence& railroad::
+userData ()
+{
+  return this->userData_;
+}
+
+void railroad::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const railroad::include_sequence& railroad::
+include () const
+{
+  return this->include_;
+}
+
+railroad::include_sequence& railroad::
+include ()
+{
+  return this->include_;
+}
+
+void railroad::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// control
+// 
+
+const control::userData_sequence& control::
+userData () const
+{
+  return this->userData_;
+}
+
+control::userData_sequence& control::
+userData ()
+{
+  return this->userData_;
+}
+
+void control::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const control::include_sequence& control::
+include () const
+{
+  return this->include_;
+}
+
+control::include_sequence& control::
+include ()
+{
+  return this->include_;
+}
+
+void control::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const control::signalId_optional& control::
+signalId () const
+{
+  return this->signalId_;
+}
+
+control::signalId_optional& control::
+signalId ()
+{
+  return this->signalId_;
+}
+
+void control::
+signalId (const signalId_type& x)
+{
+  this->signalId_.set (x);
+}
+
+void control::
+signalId (const signalId_optional& x)
+{
+  this->signalId_ = x;
+}
+
+void control::
+signalId (::std::unique_ptr< signalId_type > x)
+{
+  this->signalId_.set (std::move (x));
+}
+
+const control::type_optional& control::
+type () const
+{
+  return this->type_;
+}
+
+control::type_optional& control::
+type ()
+{
+  return this->type_;
+}
+
+void control::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void control::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void control::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// connection
+// 
+
+const connection::laneLink_sequence& connection::
+laneLink () const
+{
+  return this->laneLink_;
+}
+
+connection::laneLink_sequence& connection::
+laneLink ()
+{
+  return this->laneLink_;
+}
+
+void connection::
+laneLink (const laneLink_sequence& s)
+{
+  this->laneLink_ = s;
+}
+
+const connection::userData_sequence& connection::
+userData () const
+{
+  return this->userData_;
+}
+
+connection::userData_sequence& connection::
+userData ()
+{
+  return this->userData_;
+}
+
+void connection::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const connection::include_sequence& connection::
+include () const
+{
+  return this->include_;
+}
+
+connection::include_sequence& connection::
+include ()
+{
+  return this->include_;
+}
+
+void connection::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const connection::id_optional& connection::
+id () const
+{
+  return this->id_;
+}
+
+connection::id_optional& connection::
+id ()
+{
+  return this->id_;
+}
+
+void connection::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void connection::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void connection::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const connection::incomingRoad_optional& connection::
+incomingRoad () const
+{
+  return this->incomingRoad_;
+}
+
+connection::incomingRoad_optional& connection::
+incomingRoad ()
+{
+  return this->incomingRoad_;
+}
+
+void connection::
+incomingRoad (const incomingRoad_type& x)
+{
+  this->incomingRoad_.set (x);
+}
+
+void connection::
+incomingRoad (const incomingRoad_optional& x)
+{
+  this->incomingRoad_ = x;
+}
+
+void connection::
+incomingRoad (::std::unique_ptr< incomingRoad_type > x)
+{
+  this->incomingRoad_.set (std::move (x));
+}
+
+const connection::connectingRoad_optional& connection::
+connectingRoad () const
+{
+  return this->connectingRoad_;
+}
+
+connection::connectingRoad_optional& connection::
+connectingRoad ()
+{
+  return this->connectingRoad_;
+}
+
+void connection::
+connectingRoad (const connectingRoad_type& x)
+{
+  this->connectingRoad_.set (x);
+}
+
+void connection::
+connectingRoad (const connectingRoad_optional& x)
+{
+  this->connectingRoad_ = x;
+}
+
+void connection::
+connectingRoad (::std::unique_ptr< connectingRoad_type > x)
+{
+  this->connectingRoad_.set (std::move (x));
+}
+
+const connection::contactPoint_optional& connection::
+contactPoint () const
+{
+  return this->contactPoint_;
+}
+
+connection::contactPoint_optional& connection::
+contactPoint ()
+{
+  return this->contactPoint_;
+}
+
+void connection::
+contactPoint (const contactPoint_type& x)
+{
+  this->contactPoint_.set (x);
+}
+
+void connection::
+contactPoint (const contactPoint_optional& x)
+{
+  this->contactPoint_ = x;
+}
+
+void connection::
+contactPoint (::std::unique_ptr< contactPoint_type > x)
+{
+  this->contactPoint_.set (std::move (x));
+}
+
+
+// priority
+// 
+
+const priority::userData_sequence& priority::
+userData () const
+{
+  return this->userData_;
+}
+
+priority::userData_sequence& priority::
+userData ()
+{
+  return this->userData_;
+}
+
+void priority::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const priority::include_sequence& priority::
+include () const
+{
+  return this->include_;
+}
+
+priority::include_sequence& priority::
+include ()
+{
+  return this->include_;
+}
+
+void priority::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const priority::high_optional& priority::
+high () const
+{
+  return this->high_;
+}
+
+priority::high_optional& priority::
+high ()
+{
+  return this->high_;
+}
+
+void priority::
+high (const high_type& x)
+{
+  this->high_.set (x);
+}
+
+void priority::
+high (const high_optional& x)
+{
+  this->high_ = x;
+}
+
+void priority::
+high (::std::unique_ptr< high_type > x)
+{
+  this->high_.set (std::move (x));
+}
+
+const priority::low_optional& priority::
+low () const
+{
+  return this->low_;
+}
+
+priority::low_optional& priority::
+low ()
+{
+  return this->low_;
+}
+
+void priority::
+low (const low_type& x)
+{
+  this->low_.set (x);
+}
+
+void priority::
+low (const low_optional& x)
+{
+  this->low_ = x;
+}
+
+void priority::
+low (::std::unique_ptr< low_type > x)
+{
+  this->low_.set (std::move (x));
+}
+
+
+// controller1
+// 
+
+const controller1::userData_sequence& controller1::
+userData () const
+{
+  return this->userData_;
+}
+
+controller1::userData_sequence& controller1::
+userData ()
+{
+  return this->userData_;
+}
+
+void controller1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const controller1::include_sequence& controller1::
+include () const
+{
+  return this->include_;
+}
+
+controller1::include_sequence& controller1::
+include ()
+{
+  return this->include_;
+}
+
+void controller1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const controller1::id_optional& controller1::
+id () const
+{
+  return this->id_;
+}
+
+controller1::id_optional& controller1::
+id ()
+{
+  return this->id_;
+}
+
+void controller1::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void controller1::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void controller1::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const controller1::type_optional& controller1::
+type () const
+{
+  return this->type_;
+}
+
+controller1::type_optional& controller1::
+type ()
+{
+  return this->type_;
+}
+
+void controller1::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void controller1::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void controller1::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const controller1::sequence_optional& controller1::
+sequence () const
+{
+  return this->sequence_;
+}
+
+controller1::sequence_optional& controller1::
+sequence ()
+{
+  return this->sequence_;
+}
+
+void controller1::
+sequence (const sequence_type& x)
+{
+  this->sequence_.set (x);
+}
+
+void controller1::
+sequence (const sequence_optional& x)
+{
+  this->sequence_ = x;
+}
+
+
+// junctionReference
+// 
+
+const junctionReference::junction_optional& junctionReference::
+junction () const
+{
+  return this->junction_;
+}
+
+junctionReference::junction_optional& junctionReference::
+junction ()
+{
+  return this->junction_;
+}
+
+void junctionReference::
+junction (const junction_type& x)
+{
+  this->junction_.set (x);
+}
+
+void junctionReference::
+junction (const junction_optional& x)
+{
+  this->junction_ = x;
+}
+
+void junctionReference::
+junction (::std::unique_ptr< junction_type > x)
+{
+  this->junction_.set (std::move (x));
+}
+
+
+// platform
+// 
+
+const platform::segment_sequence& platform::
+segment () const
+{
+  return this->segment_;
+}
+
+platform::segment_sequence& platform::
+segment ()
+{
+  return this->segment_;
+}
+
+void platform::
+segment (const segment_sequence& s)
+{
+  this->segment_ = s;
+}
+
+const platform::name_optional& platform::
+name () const
+{
+  return this->name_;
+}
+
+platform::name_optional& platform::
+name ()
+{
+  return this->name_;
+}
+
+void platform::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void platform::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void platform::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const platform::id_optional& platform::
+id () const
+{
+  return this->id_;
+}
+
+platform::id_optional& platform::
+id ()
+{
+  return this->id_;
+}
+
+void platform::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void platform::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void platform::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+
+// line
+// 
+
+const line::length_optional& line::
+length () const
+{
+  return this->length_;
+}
+
+line::length_optional& line::
+length ()
+{
+  return this->length_;
+}
+
+void line::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void line::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const line::space_optional& line::
+space () const
+{
+  return this->space_;
+}
+
+line::space_optional& line::
+space ()
+{
+  return this->space_;
+}
+
+void line::
+space (const space_type& x)
+{
+  this->space_.set (x);
+}
+
+void line::
+space (const space_optional& x)
+{
+  this->space_ = x;
+}
+
+const line::tOffset_optional& line::
+tOffset () const
+{
+  return this->tOffset_;
+}
+
+line::tOffset_optional& line::
+tOffset ()
+{
+  return this->tOffset_;
+}
+
+void line::
+tOffset (const tOffset_type& x)
+{
+  this->tOffset_.set (x);
+}
+
+void line::
+tOffset (const tOffset_optional& x)
+{
+  this->tOffset_ = x;
+}
+
+const line::sOffset_optional& line::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+line::sOffset_optional& line::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void line::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void line::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const line::rule_optional& line::
+rule () const
+{
+  return this->rule_;
+}
+
+line::rule_optional& line::
+rule ()
+{
+  return this->rule_;
+}
+
+void line::
+rule (const rule_type& x)
+{
+  this->rule_.set (x);
+}
+
+void line::
+rule (const rule_optional& x)
+{
+  this->rule_ = x;
+}
+
+void line::
+rule (::std::unique_ptr< rule_type > x)
+{
+  this->rule_.set (std::move (x));
+}
+
+const line::width_optional& line::
+width () const
+{
+  return this->width_;
+}
+
+line::width_optional& line::
+width ()
+{
+  return this->width_;
+}
+
+void line::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void line::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+
+// predecessor1
+// 
+
+const predecessor1::elementType_optional& predecessor1::
+elementType () const
+{
+  return this->elementType_;
+}
+
+predecessor1::elementType_optional& predecessor1::
+elementType ()
+{
+  return this->elementType_;
+}
+
+void predecessor1::
+elementType (const elementType_type& x)
+{
+  this->elementType_.set (x);
+}
+
+void predecessor1::
+elementType (const elementType_optional& x)
+{
+  this->elementType_ = x;
+}
+
+void predecessor1::
+elementType (::std::unique_ptr< elementType_type > x)
+{
+  this->elementType_.set (std::move (x));
+}
+
+const predecessor1::elementId_optional& predecessor1::
+elementId () const
+{
+  return this->elementId_;
+}
+
+predecessor1::elementId_optional& predecessor1::
+elementId ()
+{
+  return this->elementId_;
+}
+
+void predecessor1::
+elementId (const elementId_type& x)
+{
+  this->elementId_.set (x);
+}
+
+void predecessor1::
+elementId (const elementId_optional& x)
+{
+  this->elementId_ = x;
+}
+
+void predecessor1::
+elementId (::std::unique_ptr< elementId_type > x)
+{
+  this->elementId_.set (std::move (x));
+}
+
+const predecessor1::contactPoint_optional& predecessor1::
+contactPoint () const
+{
+  return this->contactPoint_;
+}
+
+predecessor1::contactPoint_optional& predecessor1::
+contactPoint ()
+{
+  return this->contactPoint_;
+}
+
+void predecessor1::
+contactPoint (const contactPoint_type& x)
+{
+  this->contactPoint_.set (x);
+}
+
+void predecessor1::
+contactPoint (const contactPoint_optional& x)
+{
+  this->contactPoint_ = x;
+}
+
+void predecessor1::
+contactPoint (::std::unique_ptr< contactPoint_type > x)
+{
+  this->contactPoint_.set (std::move (x));
+}
+
+
+// successor1
+// 
+
+const successor1::elementType_optional& successor1::
+elementType () const
+{
+  return this->elementType_;
+}
+
+successor1::elementType_optional& successor1::
+elementType ()
+{
+  return this->elementType_;
+}
+
+void successor1::
+elementType (const elementType_type& x)
+{
+  this->elementType_.set (x);
+}
+
+void successor1::
+elementType (const elementType_optional& x)
+{
+  this->elementType_ = x;
+}
+
+void successor1::
+elementType (::std::unique_ptr< elementType_type > x)
+{
+  this->elementType_.set (std::move (x));
+}
+
+const successor1::elementId_optional& successor1::
+elementId () const
+{
+  return this->elementId_;
+}
+
+successor1::elementId_optional& successor1::
+elementId ()
+{
+  return this->elementId_;
+}
+
+void successor1::
+elementId (const elementId_type& x)
+{
+  this->elementId_.set (x);
+}
+
+void successor1::
+elementId (const elementId_optional& x)
+{
+  this->elementId_ = x;
+}
+
+void successor1::
+elementId (::std::unique_ptr< elementId_type > x)
+{
+  this->elementId_.set (std::move (x));
+}
+
+const successor1::contactPoint_optional& successor1::
+contactPoint () const
+{
+  return this->contactPoint_;
+}
+
+successor1::contactPoint_optional& successor1::
+contactPoint ()
+{
+  return this->contactPoint_;
+}
+
+void successor1::
+contactPoint (const contactPoint_type& x)
+{
+  this->contactPoint_.set (x);
+}
+
+void successor1::
+contactPoint (const contactPoint_optional& x)
+{
+  this->contactPoint_ = x;
+}
+
+void successor1::
+contactPoint (::std::unique_ptr< contactPoint_type > x)
+{
+  this->contactPoint_.set (std::move (x));
+}
+
+
+// neighbor
+// 
+
+const neighbor::side_optional& neighbor::
+side () const
+{
+  return this->side_;
+}
+
+neighbor::side_optional& neighbor::
+side ()
+{
+  return this->side_;
+}
+
+void neighbor::
+side (const side_type& x)
+{
+  this->side_.set (x);
+}
+
+void neighbor::
+side (const side_optional& x)
+{
+  this->side_ = x;
+}
+
+void neighbor::
+side (::std::unique_ptr< side_type > x)
+{
+  this->side_.set (std::move (x));
+}
+
+const neighbor::elementId_optional& neighbor::
+elementId () const
+{
+  return this->elementId_;
+}
+
+neighbor::elementId_optional& neighbor::
+elementId ()
+{
+  return this->elementId_;
+}
+
+void neighbor::
+elementId (const elementId_type& x)
+{
+  this->elementId_.set (x);
+}
+
+void neighbor::
+elementId (const elementId_optional& x)
+{
+  this->elementId_ = x;
+}
+
+void neighbor::
+elementId (::std::unique_ptr< elementId_type > x)
+{
+  this->elementId_.set (std::move (x));
+}
+
+const neighbor::direction_optional& neighbor::
+direction () const
+{
+  return this->direction_;
+}
+
+neighbor::direction_optional& neighbor::
+direction ()
+{
+  return this->direction_;
+}
+
+void neighbor::
+direction (const direction_type& x)
+{
+  this->direction_.set (x);
+}
+
+void neighbor::
+direction (const direction_optional& x)
+{
+  this->direction_ = x;
+}
+
+void neighbor::
+direction (::std::unique_ptr< direction_type > x)
+{
+  this->direction_.set (std::move (x));
+}
+
+
+// speed1
+// 
+
+const speed1::max_optional& speed1::
+max () const
+{
+  return this->max_;
+}
+
+speed1::max_optional& speed1::
+max ()
+{
+  return this->max_;
+}
+
+void speed1::
+max (const max_type& x)
+{
+  this->max_.set (x);
+}
+
+void speed1::
+max (const max_optional& x)
+{
+  this->max_ = x;
+}
+
+void speed1::
+max (::std::unique_ptr< max_type > x)
+{
+  this->max_.set (std::move (x));
+}
+
+const speed1::unit_optional& speed1::
+unit () const
+{
+  return this->unit_;
+}
+
+speed1::unit_optional& speed1::
+unit ()
+{
+  return this->unit_;
+}
+
+void speed1::
+unit (const unit_type& x)
+{
+  this->unit_.set (x);
+}
+
+void speed1::
+unit (const unit_optional& x)
+{
+  this->unit_ = x;
+}
+
+void speed1::
+unit (::std::unique_ptr< unit_type > x)
+{
+  this->unit_.set (std::move (x));
+}
+
+
+// geometry
+// 
+
+const geometry::line_optional& geometry::
+line () const
+{
+  return this->line_;
+}
+
+geometry::line_optional& geometry::
+line ()
+{
+  return this->line_;
+}
+
+void geometry::
+line (const line_type& x)
+{
+  this->line_.set (x);
+}
+
+void geometry::
+line (const line_optional& x)
+{
+  this->line_ = x;
+}
+
+void geometry::
+line (::std::unique_ptr< line_type > x)
+{
+  this->line_.set (std::move (x));
+}
+
+const geometry::spiral_optional& geometry::
+spiral () const
+{
+  return this->spiral_;
+}
+
+geometry::spiral_optional& geometry::
+spiral ()
+{
+  return this->spiral_;
+}
+
+void geometry::
+spiral (const spiral_type& x)
+{
+  this->spiral_.set (x);
+}
+
+void geometry::
+spiral (const spiral_optional& x)
+{
+  this->spiral_ = x;
+}
+
+void geometry::
+spiral (::std::unique_ptr< spiral_type > x)
+{
+  this->spiral_.set (std::move (x));
+}
+
+const geometry::arc_optional& geometry::
+arc () const
+{
+  return this->arc_;
+}
+
+geometry::arc_optional& geometry::
+arc ()
+{
+  return this->arc_;
+}
+
+void geometry::
+arc (const arc_type& x)
+{
+  this->arc_.set (x);
+}
+
+void geometry::
+arc (const arc_optional& x)
+{
+  this->arc_ = x;
+}
+
+void geometry::
+arc (::std::unique_ptr< arc_type > x)
+{
+  this->arc_.set (std::move (x));
+}
+
+const geometry::poly3_optional& geometry::
+poly3 () const
+{
+  return this->poly3_;
+}
+
+geometry::poly3_optional& geometry::
+poly3 ()
+{
+  return this->poly3_;
+}
+
+void geometry::
+poly3 (const poly3_type& x)
+{
+  this->poly3_.set (x);
+}
+
+void geometry::
+poly3 (const poly3_optional& x)
+{
+  this->poly3_ = x;
+}
+
+void geometry::
+poly3 (::std::unique_ptr< poly3_type > x)
+{
+  this->poly3_.set (std::move (x));
+}
+
+const geometry::paramPoly3_optional& geometry::
+paramPoly3 () const
+{
+  return this->paramPoly3_;
+}
+
+geometry::paramPoly3_optional& geometry::
+paramPoly3 ()
+{
+  return this->paramPoly3_;
+}
+
+void geometry::
+paramPoly3 (const paramPoly3_type& x)
+{
+  this->paramPoly3_.set (x);
+}
+
+void geometry::
+paramPoly3 (const paramPoly3_optional& x)
+{
+  this->paramPoly3_ = x;
+}
+
+void geometry::
+paramPoly3 (::std::unique_ptr< paramPoly3_type > x)
+{
+  this->paramPoly3_.set (std::move (x));
+}
+
+const geometry::userData_sequence& geometry::
+userData () const
+{
+  return this->userData_;
+}
+
+geometry::userData_sequence& geometry::
+userData ()
+{
+  return this->userData_;
+}
+
+void geometry::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const geometry::include_sequence& geometry::
+include () const
+{
+  return this->include_;
+}
+
+geometry::include_sequence& geometry::
+include ()
+{
+  return this->include_;
+}
+
+void geometry::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const geometry::s_optional& geometry::
+s () const
+{
+  return this->s_;
+}
+
+geometry::s_optional& geometry::
+s ()
+{
+  return this->s_;
+}
+
+void geometry::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void geometry::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const geometry::x_optional& geometry::
+x () const
+{
+  return this->x_;
+}
+
+geometry::x_optional& geometry::
+x ()
+{
+  return this->x_;
+}
+
+void geometry::
+x (const x_type& x)
+{
+  this->x_.set (x);
+}
+
+void geometry::
+x (const x_optional& x)
+{
+  this->x_ = x;
+}
+
+const geometry::y_optional& geometry::
+y () const
+{
+  return this->y_;
+}
+
+geometry::y_optional& geometry::
+y ()
+{
+  return this->y_;
+}
+
+void geometry::
+y (const y_type& x)
+{
+  this->y_.set (x);
+}
+
+void geometry::
+y (const y_optional& x)
+{
+  this->y_ = x;
+}
+
+const geometry::hdg_optional& geometry::
+hdg () const
+{
+  return this->hdg_;
+}
+
+geometry::hdg_optional& geometry::
+hdg ()
+{
+  return this->hdg_;
+}
+
+void geometry::
+hdg (const hdg_type& x)
+{
+  this->hdg_.set (x);
+}
+
+void geometry::
+hdg (const hdg_optional& x)
+{
+  this->hdg_ = x;
+}
+
+const geometry::length_optional& geometry::
+length () const
+{
+  return this->length_;
+}
+
+geometry::length_optional& geometry::
+length ()
+{
+  return this->length_;
+}
+
+void geometry::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void geometry::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+
+// elevation
+// 
+
+const elevation::userData_sequence& elevation::
+userData () const
+{
+  return this->userData_;
+}
+
+elevation::userData_sequence& elevation::
+userData ()
+{
+  return this->userData_;
+}
+
+void elevation::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const elevation::include_sequence& elevation::
+include () const
+{
+  return this->include_;
+}
+
+elevation::include_sequence& elevation::
+include ()
+{
+  return this->include_;
+}
+
+void elevation::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const elevation::s_optional& elevation::
+s () const
+{
+  return this->s_;
+}
+
+elevation::s_optional& elevation::
+s ()
+{
+  return this->s_;
+}
+
+void elevation::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void elevation::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const elevation::a_optional& elevation::
+a () const
+{
+  return this->a_;
+}
+
+elevation::a_optional& elevation::
+a ()
+{
+  return this->a_;
+}
+
+void elevation::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void elevation::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const elevation::b_optional& elevation::
+b () const
+{
+  return this->b_;
+}
+
+elevation::b_optional& elevation::
+b ()
+{
+  return this->b_;
+}
+
+void elevation::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void elevation::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const elevation::c_optional& elevation::
+c () const
+{
+  return this->c_;
+}
+
+elevation::c_optional& elevation::
+c ()
+{
+  return this->c_;
+}
+
+void elevation::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void elevation::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const elevation::d_optional& elevation::
+d () const
+{
+  return this->d_;
+}
+
+elevation::d_optional& elevation::
+d ()
+{
+  return this->d_;
+}
+
+void elevation::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void elevation::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// superelevation
+// 
+
+const superelevation::userData_sequence& superelevation::
+userData () const
+{
+  return this->userData_;
+}
+
+superelevation::userData_sequence& superelevation::
+userData ()
+{
+  return this->userData_;
+}
+
+void superelevation::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const superelevation::include_sequence& superelevation::
+include () const
+{
+  return this->include_;
+}
+
+superelevation::include_sequence& superelevation::
+include ()
+{
+  return this->include_;
+}
+
+void superelevation::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const superelevation::s_optional& superelevation::
+s () const
+{
+  return this->s_;
+}
+
+superelevation::s_optional& superelevation::
+s ()
+{
+  return this->s_;
+}
+
+void superelevation::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void superelevation::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const superelevation::a_optional& superelevation::
+a () const
+{
+  return this->a_;
+}
+
+superelevation::a_optional& superelevation::
+a ()
+{
+  return this->a_;
+}
+
+void superelevation::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void superelevation::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const superelevation::b_optional& superelevation::
+b () const
+{
+  return this->b_;
+}
+
+superelevation::b_optional& superelevation::
+b ()
+{
+  return this->b_;
+}
+
+void superelevation::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void superelevation::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const superelevation::c_optional& superelevation::
+c () const
+{
+  return this->c_;
+}
+
+superelevation::c_optional& superelevation::
+c ()
+{
+  return this->c_;
+}
+
+void superelevation::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void superelevation::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const superelevation::d_optional& superelevation::
+d () const
+{
+  return this->d_;
+}
+
+superelevation::d_optional& superelevation::
+d ()
+{
+  return this->d_;
+}
+
+void superelevation::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void superelevation::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// crossfall
+// 
+
+const crossfall::userData_sequence& crossfall::
+userData () const
+{
+  return this->userData_;
+}
+
+crossfall::userData_sequence& crossfall::
+userData ()
+{
+  return this->userData_;
+}
+
+void crossfall::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const crossfall::include_sequence& crossfall::
+include () const
+{
+  return this->include_;
+}
+
+crossfall::include_sequence& crossfall::
+include ()
+{
+  return this->include_;
+}
+
+void crossfall::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const crossfall::side_optional& crossfall::
+side () const
+{
+  return this->side_;
+}
+
+crossfall::side_optional& crossfall::
+side ()
+{
+  return this->side_;
+}
+
+void crossfall::
+side (const side_type& x)
+{
+  this->side_.set (x);
+}
+
+void crossfall::
+side (const side_optional& x)
+{
+  this->side_ = x;
+}
+
+void crossfall::
+side (::std::unique_ptr< side_type > x)
+{
+  this->side_.set (std::move (x));
+}
+
+const crossfall::s_optional& crossfall::
+s () const
+{
+  return this->s_;
+}
+
+crossfall::s_optional& crossfall::
+s ()
+{
+  return this->s_;
+}
+
+void crossfall::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void crossfall::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const crossfall::a_optional& crossfall::
+a () const
+{
+  return this->a_;
+}
+
+crossfall::a_optional& crossfall::
+a ()
+{
+  return this->a_;
+}
+
+void crossfall::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void crossfall::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const crossfall::b_optional& crossfall::
+b () const
+{
+  return this->b_;
+}
+
+crossfall::b_optional& crossfall::
+b ()
+{
+  return this->b_;
+}
+
+void crossfall::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void crossfall::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const crossfall::c_optional& crossfall::
+c () const
+{
+  return this->c_;
+}
+
+crossfall::c_optional& crossfall::
+c ()
+{
+  return this->c_;
+}
+
+void crossfall::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void crossfall::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const crossfall::d_optional& crossfall::
+d () const
+{
+  return this->d_;
+}
+
+crossfall::d_optional& crossfall::
+d ()
+{
+  return this->d_;
+}
+
+void crossfall::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void crossfall::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// shape
+// 
+
+const shape::userData_sequence& shape::
+userData () const
+{
+  return this->userData_;
+}
+
+shape::userData_sequence& shape::
+userData ()
+{
+  return this->userData_;
+}
+
+void shape::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const shape::include_sequence& shape::
+include () const
+{
+  return this->include_;
+}
+
+shape::include_sequence& shape::
+include ()
+{
+  return this->include_;
+}
+
+void shape::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const shape::s_optional& shape::
+s () const
+{
+  return this->s_;
+}
+
+shape::s_optional& shape::
+s ()
+{
+  return this->s_;
+}
+
+void shape::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void shape::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const shape::t_optional& shape::
+t () const
+{
+  return this->t_;
+}
+
+shape::t_optional& shape::
+t ()
+{
+  return this->t_;
+}
+
+void shape::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void shape::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const shape::a_optional& shape::
+a () const
+{
+  return this->a_;
+}
+
+shape::a_optional& shape::
+a ()
+{
+  return this->a_;
+}
+
+void shape::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void shape::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const shape::b_optional& shape::
+b () const
+{
+  return this->b_;
+}
+
+shape::b_optional& shape::
+b ()
+{
+  return this->b_;
+}
+
+void shape::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void shape::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const shape::c_optional& shape::
+c () const
+{
+  return this->c_;
+}
+
+shape::c_optional& shape::
+c ()
+{
+  return this->c_;
+}
+
+void shape::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void shape::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const shape::d_optional& shape::
+d () const
+{
+  return this->d_;
+}
+
+shape::d_optional& shape::
+d ()
+{
+  return this->d_;
+}
+
+void shape::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void shape::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// laneOffset
+// 
+
+const laneOffset::userData_sequence& laneOffset::
+userData () const
+{
+  return this->userData_;
+}
+
+laneOffset::userData_sequence& laneOffset::
+userData ()
+{
+  return this->userData_;
+}
+
+void laneOffset::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const laneOffset::include_sequence& laneOffset::
+include () const
+{
+  return this->include_;
+}
+
+laneOffset::include_sequence& laneOffset::
+include ()
+{
+  return this->include_;
+}
+
+void laneOffset::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const laneOffset::s_optional& laneOffset::
+s () const
+{
+  return this->s_;
+}
+
+laneOffset::s_optional& laneOffset::
+s ()
+{
+  return this->s_;
+}
+
+void laneOffset::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void laneOffset::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const laneOffset::a_optional& laneOffset::
+a () const
+{
+  return this->a_;
+}
+
+laneOffset::a_optional& laneOffset::
+a ()
+{
+  return this->a_;
+}
+
+void laneOffset::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void laneOffset::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const laneOffset::b_optional& laneOffset::
+b () const
+{
+  return this->b_;
+}
+
+laneOffset::b_optional& laneOffset::
+b ()
+{
+  return this->b_;
+}
+
+void laneOffset::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void laneOffset::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const laneOffset::c_optional& laneOffset::
+c () const
+{
+  return this->c_;
+}
+
+laneOffset::c_optional& laneOffset::
+c ()
+{
+  return this->c_;
+}
+
+void laneOffset::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void laneOffset::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const laneOffset::d_optional& laneOffset::
+d () const
+{
+  return this->d_;
+}
+
+laneOffset::d_optional& laneOffset::
+d ()
+{
+  return this->d_;
+}
+
+void laneOffset::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void laneOffset::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// laneSection
+// 
+
+const laneSection::left_optional& laneSection::
+left () const
+{
+  return this->left_;
+}
+
+laneSection::left_optional& laneSection::
+left ()
+{
+  return this->left_;
+}
+
+void laneSection::
+left (const left_type& x)
+{
+  this->left_.set (x);
+}
+
+void laneSection::
+left (const left_optional& x)
+{
+  this->left_ = x;
+}
+
+void laneSection::
+left (::std::unique_ptr< left_type > x)
+{
+  this->left_.set (std::move (x));
+}
+
+const laneSection::center_type& laneSection::
+center () const
+{
+  return this->center_.get ();
+}
+
+laneSection::center_type& laneSection::
+center ()
+{
+  return this->center_.get ();
+}
+
+void laneSection::
+center (const center_type& x)
+{
+  this->center_.set (x);
+}
+
+void laneSection::
+center (::std::unique_ptr< center_type > x)
+{
+  this->center_.set (std::move (x));
+}
+
+const laneSection::right_optional& laneSection::
+right () const
+{
+  return this->right_;
+}
+
+laneSection::right_optional& laneSection::
+right ()
+{
+  return this->right_;
+}
+
+void laneSection::
+right (const right_type& x)
+{
+  this->right_.set (x);
+}
+
+void laneSection::
+right (const right_optional& x)
+{
+  this->right_ = x;
+}
+
+void laneSection::
+right (::std::unique_ptr< right_type > x)
+{
+  this->right_.set (std::move (x));
+}
+
+const laneSection::userData_sequence& laneSection::
+userData () const
+{
+  return this->userData_;
+}
+
+laneSection::userData_sequence& laneSection::
+userData ()
+{
+  return this->userData_;
+}
+
+void laneSection::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const laneSection::include_sequence& laneSection::
+include () const
+{
+  return this->include_;
+}
+
+laneSection::include_sequence& laneSection::
+include ()
+{
+  return this->include_;
+}
+
+void laneSection::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const laneSection::s_optional& laneSection::
+s () const
+{
+  return this->s_;
+}
+
+laneSection::s_optional& laneSection::
+s ()
+{
+  return this->s_;
+}
+
+void laneSection::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void laneSection::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const laneSection::singleSide_optional& laneSection::
+singleSide () const
+{
+  return this->singleSide_;
+}
+
+laneSection::singleSide_optional& laneSection::
+singleSide ()
+{
+  return this->singleSide_;
+}
+
+void laneSection::
+singleSide (const singleSide_type& x)
+{
+  this->singleSide_.set (x);
+}
+
+void laneSection::
+singleSide (const singleSide_optional& x)
+{
+  this->singleSide_ = x;
+}
+
+void laneSection::
+singleSide (::std::unique_ptr< singleSide_type > x)
+{
+  this->singleSide_.set (std::move (x));
+}
+
+
+// object
+// 
+
+const object::repeat_sequence& object::
+repeat () const
+{
+  return this->repeat_;
+}
+
+object::repeat_sequence& object::
+repeat ()
+{
+  return this->repeat_;
+}
+
+void object::
+repeat (const repeat_sequence& s)
+{
+  this->repeat_ = s;
+}
+
+const object::outline_optional& object::
+outline () const
+{
+  return this->outline_;
+}
+
+object::outline_optional& object::
+outline ()
+{
+  return this->outline_;
+}
+
+void object::
+outline (const outline_type& x)
+{
+  this->outline_.set (x);
+}
+
+void object::
+outline (const outline_optional& x)
+{
+  this->outline_ = x;
+}
+
+void object::
+outline (::std::unique_ptr< outline_type > x)
+{
+  this->outline_.set (std::move (x));
+}
+
+const object::material_optional& object::
+material () const
+{
+  return this->material_;
+}
+
+object::material_optional& object::
+material ()
+{
+  return this->material_;
+}
+
+void object::
+material (const material_type& x)
+{
+  this->material_.set (x);
+}
+
+void object::
+material (const material_optional& x)
+{
+  this->material_ = x;
+}
+
+void object::
+material (::std::unique_ptr< material_type > x)
+{
+  this->material_.set (std::move (x));
+}
+
+const object::validity_sequence& object::
+validity () const
+{
+  return this->validity_;
+}
+
+object::validity_sequence& object::
+validity ()
+{
+  return this->validity_;
+}
+
+void object::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const object::parkingSpace_optional& object::
+parkingSpace () const
+{
+  return this->parkingSpace_;
+}
+
+object::parkingSpace_optional& object::
+parkingSpace ()
+{
+  return this->parkingSpace_;
+}
+
+void object::
+parkingSpace (const parkingSpace_type& x)
+{
+  this->parkingSpace_.set (x);
+}
+
+void object::
+parkingSpace (const parkingSpace_optional& x)
+{
+  this->parkingSpace_ = x;
+}
+
+void object::
+parkingSpace (::std::unique_ptr< parkingSpace_type > x)
+{
+  this->parkingSpace_.set (std::move (x));
+}
+
+const object::userData_sequence& object::
+userData () const
+{
+  return this->userData_;
+}
+
+object::userData_sequence& object::
+userData ()
+{
+  return this->userData_;
+}
+
+void object::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const object::include_sequence& object::
+include () const
+{
+  return this->include_;
+}
+
+object::include_sequence& object::
+include ()
+{
+  return this->include_;
+}
+
+void object::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const object::type_optional& object::
+type () const
+{
+  return this->type_;
+}
+
+object::type_optional& object::
+type ()
+{
+  return this->type_;
+}
+
+void object::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void object::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void object::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const object::name_optional& object::
+name () const
+{
+  return this->name_;
+}
+
+object::name_optional& object::
+name ()
+{
+  return this->name_;
+}
+
+void object::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void object::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void object::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const object::id_optional& object::
+id () const
+{
+  return this->id_;
+}
+
+object::id_optional& object::
+id ()
+{
+  return this->id_;
+}
+
+void object::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void object::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void object::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const object::s_optional& object::
+s () const
+{
+  return this->s_;
+}
+
+object::s_optional& object::
+s ()
+{
+  return this->s_;
+}
+
+void object::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void object::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const object::t_optional& object::
+t () const
+{
+  return this->t_;
+}
+
+object::t_optional& object::
+t ()
+{
+  return this->t_;
+}
+
+void object::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void object::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const object::zOffset_optional& object::
+zOffset () const
+{
+  return this->zOffset_;
+}
+
+object::zOffset_optional& object::
+zOffset ()
+{
+  return this->zOffset_;
+}
+
+void object::
+zOffset (const zOffset_type& x)
+{
+  this->zOffset_.set (x);
+}
+
+void object::
+zOffset (const zOffset_optional& x)
+{
+  this->zOffset_ = x;
+}
+
+const object::validLength_optional& object::
+validLength () const
+{
+  return this->validLength_;
+}
+
+object::validLength_optional& object::
+validLength ()
+{
+  return this->validLength_;
+}
+
+void object::
+validLength (const validLength_type& x)
+{
+  this->validLength_.set (x);
+}
+
+void object::
+validLength (const validLength_optional& x)
+{
+  this->validLength_ = x;
+}
+
+const object::orientation_optional& object::
+orientation () const
+{
+  return this->orientation_;
+}
+
+object::orientation_optional& object::
+orientation ()
+{
+  return this->orientation_;
+}
+
+void object::
+orientation (const orientation_type& x)
+{
+  this->orientation_.set (x);
+}
+
+void object::
+orientation (const orientation_optional& x)
+{
+  this->orientation_ = x;
+}
+
+void object::
+orientation (::std::unique_ptr< orientation_type > x)
+{
+  this->orientation_.set (std::move (x));
+}
+
+const object::length_optional& object::
+length () const
+{
+  return this->length_;
+}
+
+object::length_optional& object::
+length ()
+{
+  return this->length_;
+}
+
+void object::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void object::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const object::width_optional& object::
+width () const
+{
+  return this->width_;
+}
+
+object::width_optional& object::
+width ()
+{
+  return this->width_;
+}
+
+void object::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void object::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+const object::radius_optional& object::
+radius () const
+{
+  return this->radius_;
+}
+
+object::radius_optional& object::
+radius ()
+{
+  return this->radius_;
+}
+
+void object::
+radius (const radius_type& x)
+{
+  this->radius_.set (x);
+}
+
+void object::
+radius (const radius_optional& x)
+{
+  this->radius_ = x;
+}
+
+const object::height_optional& object::
+height () const
+{
+  return this->height_;
+}
+
+object::height_optional& object::
+height ()
+{
+  return this->height_;
+}
+
+void object::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void object::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+const object::hdg_optional& object::
+hdg () const
+{
+  return this->hdg_;
+}
+
+object::hdg_optional& object::
+hdg ()
+{
+  return this->hdg_;
+}
+
+void object::
+hdg (const hdg_type& x)
+{
+  this->hdg_.set (x);
+}
+
+void object::
+hdg (const hdg_optional& x)
+{
+  this->hdg_ = x;
+}
+
+const object::pitch_optional& object::
+pitch () const
+{
+  return this->pitch_;
+}
+
+object::pitch_optional& object::
+pitch ()
+{
+  return this->pitch_;
+}
+
+void object::
+pitch (const pitch_type& x)
+{
+  this->pitch_.set (x);
+}
+
+void object::
+pitch (const pitch_optional& x)
+{
+  this->pitch_ = x;
+}
+
+const object::roll_optional& object::
+roll () const
+{
+  return this->roll_;
+}
+
+object::roll_optional& object::
+roll ()
+{
+  return this->roll_;
+}
+
+void object::
+roll (const roll_type& x)
+{
+  this->roll_.set (x);
+}
+
+void object::
+roll (const roll_optional& x)
+{
+  this->roll_ = x;
+}
+
+
+// objectReference
+// 
+
+const objectReference::validity_sequence& objectReference::
+validity () const
+{
+  return this->validity_;
+}
+
+objectReference::validity_sequence& objectReference::
+validity ()
+{
+  return this->validity_;
+}
+
+void objectReference::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const objectReference::userData_sequence& objectReference::
+userData () const
+{
+  return this->userData_;
+}
+
+objectReference::userData_sequence& objectReference::
+userData ()
+{
+  return this->userData_;
+}
+
+void objectReference::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const objectReference::include_sequence& objectReference::
+include () const
+{
+  return this->include_;
+}
+
+objectReference::include_sequence& objectReference::
+include ()
+{
+  return this->include_;
+}
+
+void objectReference::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const objectReference::s_optional& objectReference::
+s () const
+{
+  return this->s_;
+}
+
+objectReference::s_optional& objectReference::
+s ()
+{
+  return this->s_;
+}
+
+void objectReference::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void objectReference::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const objectReference::t_optional& objectReference::
+t () const
+{
+  return this->t_;
+}
+
+objectReference::t_optional& objectReference::
+t ()
+{
+  return this->t_;
+}
+
+void objectReference::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void objectReference::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const objectReference::id_optional& objectReference::
+id () const
+{
+  return this->id_;
+}
+
+objectReference::id_optional& objectReference::
+id ()
+{
+  return this->id_;
+}
+
+void objectReference::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void objectReference::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void objectReference::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const objectReference::zOffset_optional& objectReference::
+zOffset () const
+{
+  return this->zOffset_;
+}
+
+objectReference::zOffset_optional& objectReference::
+zOffset ()
+{
+  return this->zOffset_;
+}
+
+void objectReference::
+zOffset (const zOffset_type& x)
+{
+  this->zOffset_.set (x);
+}
+
+void objectReference::
+zOffset (const zOffset_optional& x)
+{
+  this->zOffset_ = x;
+}
+
+const objectReference::validLength_optional& objectReference::
+validLength () const
+{
+  return this->validLength_;
+}
+
+objectReference::validLength_optional& objectReference::
+validLength ()
+{
+  return this->validLength_;
+}
+
+void objectReference::
+validLength (const validLength_type& x)
+{
+  this->validLength_.set (x);
+}
+
+void objectReference::
+validLength (const validLength_optional& x)
+{
+  this->validLength_ = x;
+}
+
+const objectReference::orientation_optional& objectReference::
+orientation () const
+{
+  return this->orientation_;
+}
+
+objectReference::orientation_optional& objectReference::
+orientation ()
+{
+  return this->orientation_;
+}
+
+void objectReference::
+orientation (const orientation_type& x)
+{
+  this->orientation_.set (x);
+}
+
+void objectReference::
+orientation (const orientation_optional& x)
+{
+  this->orientation_ = x;
+}
+
+void objectReference::
+orientation (::std::unique_ptr< orientation_type > x)
+{
+  this->orientation_.set (std::move (x));
+}
+
+
+// tunnel
+// 
+
+const tunnel::validity_sequence& tunnel::
+validity () const
+{
+  return this->validity_;
+}
+
+tunnel::validity_sequence& tunnel::
+validity ()
+{
+  return this->validity_;
+}
+
+void tunnel::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const tunnel::userData_sequence& tunnel::
+userData () const
+{
+  return this->userData_;
+}
+
+tunnel::userData_sequence& tunnel::
+userData ()
+{
+  return this->userData_;
+}
+
+void tunnel::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const tunnel::include_sequence& tunnel::
+include () const
+{
+  return this->include_;
+}
+
+tunnel::include_sequence& tunnel::
+include ()
+{
+  return this->include_;
+}
+
+void tunnel::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const tunnel::s_optional& tunnel::
+s () const
+{
+  return this->s_;
+}
+
+tunnel::s_optional& tunnel::
+s ()
+{
+  return this->s_;
+}
+
+void tunnel::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void tunnel::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const tunnel::length_optional& tunnel::
+length () const
+{
+  return this->length_;
+}
+
+tunnel::length_optional& tunnel::
+length ()
+{
+  return this->length_;
+}
+
+void tunnel::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void tunnel::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const tunnel::name_optional& tunnel::
+name () const
+{
+  return this->name_;
+}
+
+tunnel::name_optional& tunnel::
+name ()
+{
+  return this->name_;
+}
+
+void tunnel::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void tunnel::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void tunnel::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const tunnel::id_optional& tunnel::
+id () const
+{
+  return this->id_;
+}
+
+tunnel::id_optional& tunnel::
+id ()
+{
+  return this->id_;
+}
+
+void tunnel::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void tunnel::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void tunnel::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const tunnel::type_optional& tunnel::
+type () const
+{
+  return this->type_;
+}
+
+tunnel::type_optional& tunnel::
+type ()
+{
+  return this->type_;
+}
+
+void tunnel::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void tunnel::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void tunnel::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const tunnel::lighting_optional& tunnel::
+lighting () const
+{
+  return this->lighting_;
+}
+
+tunnel::lighting_optional& tunnel::
+lighting ()
+{
+  return this->lighting_;
+}
+
+void tunnel::
+lighting (const lighting_type& x)
+{
+  this->lighting_.set (x);
+}
+
+void tunnel::
+lighting (const lighting_optional& x)
+{
+  this->lighting_ = x;
+}
+
+const tunnel::daylight_optional& tunnel::
+daylight () const
+{
+  return this->daylight_;
+}
+
+tunnel::daylight_optional& tunnel::
+daylight ()
+{
+  return this->daylight_;
+}
+
+void tunnel::
+daylight (const daylight_type& x)
+{
+  this->daylight_.set (x);
+}
+
+void tunnel::
+daylight (const daylight_optional& x)
+{
+  this->daylight_ = x;
+}
+
+
+// bridge
+// 
+
+const bridge::validity_sequence& bridge::
+validity () const
+{
+  return this->validity_;
+}
+
+bridge::validity_sequence& bridge::
+validity ()
+{
+  return this->validity_;
+}
+
+void bridge::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const bridge::userData_sequence& bridge::
+userData () const
+{
+  return this->userData_;
+}
+
+bridge::userData_sequence& bridge::
+userData ()
+{
+  return this->userData_;
+}
+
+void bridge::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const bridge::include_sequence& bridge::
+include () const
+{
+  return this->include_;
+}
+
+bridge::include_sequence& bridge::
+include ()
+{
+  return this->include_;
+}
+
+void bridge::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const bridge::s_optional& bridge::
+s () const
+{
+  return this->s_;
+}
+
+bridge::s_optional& bridge::
+s ()
+{
+  return this->s_;
+}
+
+void bridge::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void bridge::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const bridge::length_optional& bridge::
+length () const
+{
+  return this->length_;
+}
+
+bridge::length_optional& bridge::
+length ()
+{
+  return this->length_;
+}
+
+void bridge::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void bridge::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const bridge::name_optional& bridge::
+name () const
+{
+  return this->name_;
+}
+
+bridge::name_optional& bridge::
+name ()
+{
+  return this->name_;
+}
+
+void bridge::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void bridge::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void bridge::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const bridge::id_optional& bridge::
+id () const
+{
+  return this->id_;
+}
+
+bridge::id_optional& bridge::
+id ()
+{
+  return this->id_;
+}
+
+void bridge::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void bridge::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void bridge::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const bridge::type_optional& bridge::
+type () const
+{
+  return this->type_;
+}
+
+bridge::type_optional& bridge::
+type ()
+{
+  return this->type_;
+}
+
+void bridge::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void bridge::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void bridge::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// signal
+// 
+
+const signal::validity_sequence& signal::
+validity () const
+{
+  return this->validity_;
+}
+
+signal::validity_sequence& signal::
+validity ()
+{
+  return this->validity_;
+}
+
+void signal::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const signal::dependency_sequence& signal::
+dependency () const
+{
+  return this->dependency_;
+}
+
+signal::dependency_sequence& signal::
+dependency ()
+{
+  return this->dependency_;
+}
+
+void signal::
+dependency (const dependency_sequence& s)
+{
+  this->dependency_ = s;
+}
+
+const signal::userData_sequence& signal::
+userData () const
+{
+  return this->userData_;
+}
+
+signal::userData_sequence& signal::
+userData ()
+{
+  return this->userData_;
+}
+
+void signal::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const signal::include_sequence& signal::
+include () const
+{
+  return this->include_;
+}
+
+signal::include_sequence& signal::
+include ()
+{
+  return this->include_;
+}
+
+void signal::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const signal::s_optional& signal::
+s () const
+{
+  return this->s_;
+}
+
+signal::s_optional& signal::
+s ()
+{
+  return this->s_;
+}
+
+void signal::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void signal::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const signal::t_optional& signal::
+t () const
+{
+  return this->t_;
+}
+
+signal::t_optional& signal::
+t ()
+{
+  return this->t_;
+}
+
+void signal::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void signal::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const signal::id_optional& signal::
+id () const
+{
+  return this->id_;
+}
+
+signal::id_optional& signal::
+id ()
+{
+  return this->id_;
+}
+
+void signal::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void signal::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void signal::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const signal::name_optional& signal::
+name () const
+{
+  return this->name_;
+}
+
+signal::name_optional& signal::
+name ()
+{
+  return this->name_;
+}
+
+void signal::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void signal::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void signal::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const signal::dynamic_optional& signal::
+dynamic () const
+{
+  return this->dynamic_;
+}
+
+signal::dynamic_optional& signal::
+dynamic ()
+{
+  return this->dynamic_;
+}
+
+void signal::
+dynamic (const dynamic_type& x)
+{
+  this->dynamic_.set (x);
+}
+
+void signal::
+dynamic (const dynamic_optional& x)
+{
+  this->dynamic_ = x;
+}
+
+void signal::
+dynamic (::std::unique_ptr< dynamic_type > x)
+{
+  this->dynamic_.set (std::move (x));
+}
+
+const signal::orientation_optional& signal::
+orientation () const
+{
+  return this->orientation_;
+}
+
+signal::orientation_optional& signal::
+orientation ()
+{
+  return this->orientation_;
+}
+
+void signal::
+orientation (const orientation_type& x)
+{
+  this->orientation_.set (x);
+}
+
+void signal::
+orientation (const orientation_optional& x)
+{
+  this->orientation_ = x;
+}
+
+void signal::
+orientation (::std::unique_ptr< orientation_type > x)
+{
+  this->orientation_.set (std::move (x));
+}
+
+const signal::zOffset_optional& signal::
+zOffset () const
+{
+  return this->zOffset_;
+}
+
+signal::zOffset_optional& signal::
+zOffset ()
+{
+  return this->zOffset_;
+}
+
+void signal::
+zOffset (const zOffset_type& x)
+{
+  this->zOffset_.set (x);
+}
+
+void signal::
+zOffset (const zOffset_optional& x)
+{
+  this->zOffset_ = x;
+}
+
+const signal::country_optional& signal::
+country () const
+{
+  return this->country_;
+}
+
+signal::country_optional& signal::
+country ()
+{
+  return this->country_;
+}
+
+void signal::
+country (const country_type& x)
+{
+  this->country_.set (x);
+}
+
+void signal::
+country (const country_optional& x)
+{
+  this->country_ = x;
+}
+
+void signal::
+country (::std::unique_ptr< country_type > x)
+{
+  this->country_.set (std::move (x));
+}
+
+const signal::type_optional& signal::
+type () const
+{
+  return this->type_;
+}
+
+signal::type_optional& signal::
+type ()
+{
+  return this->type_;
+}
+
+void signal::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void signal::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void signal::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+const signal::subtype_optional& signal::
+subtype () const
+{
+  return this->subtype_;
+}
+
+signal::subtype_optional& signal::
+subtype ()
+{
+  return this->subtype_;
+}
+
+void signal::
+subtype (const subtype_type& x)
+{
+  this->subtype_.set (x);
+}
+
+void signal::
+subtype (const subtype_optional& x)
+{
+  this->subtype_ = x;
+}
+
+void signal::
+subtype (::std::unique_ptr< subtype_type > x)
+{
+  this->subtype_.set (std::move (x));
+}
+
+const signal::value_optional& signal::
+value () const
+{
+  return this->value_;
+}
+
+signal::value_optional& signal::
+value ()
+{
+  return this->value_;
+}
+
+void signal::
+value (const value_type& x)
+{
+  this->value_.set (x);
+}
+
+void signal::
+value (const value_optional& x)
+{
+  this->value_ = x;
+}
+
+const signal::unit_optional& signal::
+unit () const
+{
+  return this->unit_;
+}
+
+signal::unit_optional& signal::
+unit ()
+{
+  return this->unit_;
+}
+
+void signal::
+unit (const unit_type& x)
+{
+  this->unit_.set (x);
+}
+
+void signal::
+unit (const unit_optional& x)
+{
+  this->unit_ = x;
+}
+
+void signal::
+unit (::std::unique_ptr< unit_type > x)
+{
+  this->unit_.set (std::move (x));
+}
+
+const signal::height_optional& signal::
+height () const
+{
+  return this->height_;
+}
+
+signal::height_optional& signal::
+height ()
+{
+  return this->height_;
+}
+
+void signal::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void signal::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+const signal::width_optional& signal::
+width () const
+{
+  return this->width_;
+}
+
+signal::width_optional& signal::
+width ()
+{
+  return this->width_;
+}
+
+void signal::
+width (const width_type& x)
+{
+  this->width_.set (x);
+}
+
+void signal::
+width (const width_optional& x)
+{
+  this->width_ = x;
+}
+
+const signal::text_optional& signal::
+text () const
+{
+  return this->text_;
+}
+
+signal::text_optional& signal::
+text ()
+{
+  return this->text_;
+}
+
+void signal::
+text (const text_type& x)
+{
+  this->text_.set (x);
+}
+
+void signal::
+text (const text_optional& x)
+{
+  this->text_ = x;
+}
+
+void signal::
+text (::std::unique_ptr< text_type > x)
+{
+  this->text_.set (std::move (x));
+}
+
+const signal::hOffset_optional& signal::
+hOffset () const
+{
+  return this->hOffset_;
+}
+
+signal::hOffset_optional& signal::
+hOffset ()
+{
+  return this->hOffset_;
+}
+
+void signal::
+hOffset (const hOffset_type& x)
+{
+  this->hOffset_.set (x);
+}
+
+void signal::
+hOffset (const hOffset_optional& x)
+{
+  this->hOffset_ = x;
+}
+
+const signal::pitch_optional& signal::
+pitch () const
+{
+  return this->pitch_;
+}
+
+signal::pitch_optional& signal::
+pitch ()
+{
+  return this->pitch_;
+}
+
+void signal::
+pitch (const pitch_type& x)
+{
+  this->pitch_.set (x);
+}
+
+void signal::
+pitch (const pitch_optional& x)
+{
+  this->pitch_ = x;
+}
+
+const signal::roll_optional& signal::
+roll () const
+{
+  return this->roll_;
+}
+
+signal::roll_optional& signal::
+roll ()
+{
+  return this->roll_;
+}
+
+void signal::
+roll (const roll_type& x)
+{
+  this->roll_.set (x);
+}
+
+void signal::
+roll (const roll_optional& x)
+{
+  this->roll_ = x;
+}
+
+
+// signalReference
+// 
+
+const signalReference::validity_sequence& signalReference::
+validity () const
+{
+  return this->validity_;
+}
+
+signalReference::validity_sequence& signalReference::
+validity ()
+{
+  return this->validity_;
+}
+
+void signalReference::
+validity (const validity_sequence& s)
+{
+  this->validity_ = s;
+}
+
+const signalReference::userData_sequence& signalReference::
+userData () const
+{
+  return this->userData_;
+}
+
+signalReference::userData_sequence& signalReference::
+userData ()
+{
+  return this->userData_;
+}
+
+void signalReference::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const signalReference::include_sequence& signalReference::
+include () const
+{
+  return this->include_;
+}
+
+signalReference::include_sequence& signalReference::
+include ()
+{
+  return this->include_;
+}
+
+void signalReference::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const signalReference::s_optional& signalReference::
+s () const
+{
+  return this->s_;
+}
+
+signalReference::s_optional& signalReference::
+s ()
+{
+  return this->s_;
+}
+
+void signalReference::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void signalReference::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const signalReference::t_optional& signalReference::
+t () const
+{
+  return this->t_;
+}
+
+signalReference::t_optional& signalReference::
+t ()
+{
+  return this->t_;
+}
+
+void signalReference::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void signalReference::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const signalReference::id_optional& signalReference::
+id () const
+{
+  return this->id_;
+}
+
+signalReference::id_optional& signalReference::
+id ()
+{
+  return this->id_;
+}
+
+void signalReference::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void signalReference::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void signalReference::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const signalReference::orientation_optional& signalReference::
+orientation () const
+{
+  return this->orientation_;
+}
+
+signalReference::orientation_optional& signalReference::
+orientation ()
+{
+  return this->orientation_;
+}
+
+void signalReference::
+orientation (const orientation_type& x)
+{
+  this->orientation_.set (x);
+}
+
+void signalReference::
+orientation (const orientation_optional& x)
+{
+  this->orientation_ = x;
+}
+
+void signalReference::
+orientation (::std::unique_ptr< orientation_type > x)
+{
+  this->orientation_.set (std::move (x));
+}
+
+
+// CRG
+// 
+
+const CRG::userData_sequence& CRG::
+userData () const
+{
+  return this->userData_;
+}
+
+CRG::userData_sequence& CRG::
+userData ()
+{
+  return this->userData_;
+}
+
+void CRG::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const CRG::include_sequence& CRG::
+include () const
+{
+  return this->include_;
+}
+
+CRG::include_sequence& CRG::
+include ()
+{
+  return this->include_;
+}
+
+void CRG::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const CRG::file_optional& CRG::
+file () const
+{
+  return this->file_;
+}
+
+CRG::file_optional& CRG::
+file ()
+{
+  return this->file_;
+}
+
+void CRG::
+file (const file_type& x)
+{
+  this->file_.set (x);
+}
+
+void CRG::
+file (const file_optional& x)
+{
+  this->file_ = x;
+}
+
+void CRG::
+file (::std::unique_ptr< file_type > x)
+{
+  this->file_.set (std::move (x));
+}
+
+const CRG::sStart_optional& CRG::
+sStart () const
+{
+  return this->sStart_;
+}
+
+CRG::sStart_optional& CRG::
+sStart ()
+{
+  return this->sStart_;
+}
+
+void CRG::
+sStart (const sStart_type& x)
+{
+  this->sStart_.set (x);
+}
+
+void CRG::
+sStart (const sStart_optional& x)
+{
+  this->sStart_ = x;
+}
+
+const CRG::sEnd_optional& CRG::
+sEnd () const
+{
+  return this->sEnd_;
+}
+
+CRG::sEnd_optional& CRG::
+sEnd ()
+{
+  return this->sEnd_;
+}
+
+void CRG::
+sEnd (const sEnd_type& x)
+{
+  this->sEnd_.set (x);
+}
+
+void CRG::
+sEnd (const sEnd_optional& x)
+{
+  this->sEnd_ = x;
+}
+
+const CRG::orientation_optional& CRG::
+orientation () const
+{
+  return this->orientation_;
+}
+
+CRG::orientation_optional& CRG::
+orientation ()
+{
+  return this->orientation_;
+}
+
+void CRG::
+orientation (const orientation_type& x)
+{
+  this->orientation_.set (x);
+}
+
+void CRG::
+orientation (const orientation_optional& x)
+{
+  this->orientation_ = x;
+}
+
+void CRG::
+orientation (::std::unique_ptr< orientation_type > x)
+{
+  this->orientation_.set (std::move (x));
+}
+
+const CRG::mode_optional& CRG::
+mode () const
+{
+  return this->mode_;
+}
+
+CRG::mode_optional& CRG::
+mode ()
+{
+  return this->mode_;
+}
+
+void CRG::
+mode (const mode_type& x)
+{
+  this->mode_.set (x);
+}
+
+void CRG::
+mode (const mode_optional& x)
+{
+  this->mode_ = x;
+}
+
+void CRG::
+mode (::std::unique_ptr< mode_type > x)
+{
+  this->mode_.set (std::move (x));
+}
+
+const CRG::purpose_optional& CRG::
+purpose () const
+{
+  return this->purpose_;
+}
+
+CRG::purpose_optional& CRG::
+purpose ()
+{
+  return this->purpose_;
+}
+
+void CRG::
+purpose (const purpose_type& x)
+{
+  this->purpose_.set (x);
+}
+
+void CRG::
+purpose (const purpose_optional& x)
+{
+  this->purpose_ = x;
+}
+
+void CRG::
+purpose (::std::unique_ptr< purpose_type > x)
+{
+  this->purpose_.set (std::move (x));
+}
+
+const CRG::sOffset_optional& CRG::
+sOffset () const
+{
+  return this->sOffset_;
+}
+
+CRG::sOffset_optional& CRG::
+sOffset ()
+{
+  return this->sOffset_;
+}
+
+void CRG::
+sOffset (const sOffset_type& x)
+{
+  this->sOffset_.set (x);
+}
+
+void CRG::
+sOffset (const sOffset_optional& x)
+{
+  this->sOffset_ = x;
+}
+
+const CRG::tOffset_optional& CRG::
+tOffset () const
+{
+  return this->tOffset_;
+}
+
+CRG::tOffset_optional& CRG::
+tOffset ()
+{
+  return this->tOffset_;
+}
+
+void CRG::
+tOffset (const tOffset_type& x)
+{
+  this->tOffset_.set (x);
+}
+
+void CRG::
+tOffset (const tOffset_optional& x)
+{
+  this->tOffset_ = x;
+}
+
+const CRG::zOffset_optional& CRG::
+zOffset () const
+{
+  return this->zOffset_;
+}
+
+CRG::zOffset_optional& CRG::
+zOffset ()
+{
+  return this->zOffset_;
+}
+
+void CRG::
+zOffset (const zOffset_type& x)
+{
+  this->zOffset_.set (x);
+}
+
+void CRG::
+zOffset (const zOffset_optional& x)
+{
+  this->zOffset_ = x;
+}
+
+const CRG::zScale_optional& CRG::
+zScale () const
+{
+  return this->zScale_;
+}
+
+CRG::zScale_optional& CRG::
+zScale ()
+{
+  return this->zScale_;
+}
+
+void CRG::
+zScale (const zScale_type& x)
+{
+  this->zScale_.set (x);
+}
+
+void CRG::
+zScale (const zScale_optional& x)
+{
+  this->zScale_ = x;
+}
+
+const CRG::hOffset_optional& CRG::
+hOffset () const
+{
+  return this->hOffset_;
+}
+
+CRG::hOffset_optional& CRG::
+hOffset ()
+{
+  return this->hOffset_;
+}
+
+void CRG::
+hOffset (const hOffset_type& x)
+{
+  this->hOffset_.set (x);
+}
+
+void CRG::
+hOffset (const hOffset_optional& x)
+{
+  this->hOffset_ = x;
+}
+
+
+// switch_
+// 
+
+const switch_::mainTrack_type& switch_::
+mainTrack () const
+{
+  return this->mainTrack_.get ();
+}
+
+switch_::mainTrack_type& switch_::
+mainTrack ()
+{
+  return this->mainTrack_.get ();
+}
+
+void switch_::
+mainTrack (const mainTrack_type& x)
+{
+  this->mainTrack_.set (x);
+}
+
+void switch_::
+mainTrack (::std::unique_ptr< mainTrack_type > x)
+{
+  this->mainTrack_.set (std::move (x));
+}
+
+const switch_::sideTrack_type& switch_::
+sideTrack () const
+{
+  return this->sideTrack_.get ();
+}
+
+switch_::sideTrack_type& switch_::
+sideTrack ()
+{
+  return this->sideTrack_.get ();
+}
+
+void switch_::
+sideTrack (const sideTrack_type& x)
+{
+  this->sideTrack_.set (x);
+}
+
+void switch_::
+sideTrack (::std::unique_ptr< sideTrack_type > x)
+{
+  this->sideTrack_.set (std::move (x));
+}
+
+const switch_::partner_optional& switch_::
+partner () const
+{
+  return this->partner_;
+}
+
+switch_::partner_optional& switch_::
+partner ()
+{
+  return this->partner_;
+}
+
+void switch_::
+partner (const partner_type& x)
+{
+  this->partner_.set (x);
+}
+
+void switch_::
+partner (const partner_optional& x)
+{
+  this->partner_ = x;
+}
+
+void switch_::
+partner (::std::unique_ptr< partner_type > x)
+{
+  this->partner_.set (std::move (x));
+}
+
+const switch_::userData_sequence& switch_::
+userData () const
+{
+  return this->userData_;
+}
+
+switch_::userData_sequence& switch_::
+userData ()
+{
+  return this->userData_;
+}
+
+void switch_::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const switch_::include_sequence& switch_::
+include () const
+{
+  return this->include_;
+}
+
+switch_::include_sequence& switch_::
+include ()
+{
+  return this->include_;
+}
+
+void switch_::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const switch_::name_optional& switch_::
+name () const
+{
+  return this->name_;
+}
+
+switch_::name_optional& switch_::
+name ()
+{
+  return this->name_;
+}
+
+void switch_::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void switch_::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void switch_::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const switch_::id_optional& switch_::
+id () const
+{
+  return this->id_;
+}
+
+switch_::id_optional& switch_::
+id ()
+{
+  return this->id_;
+}
+
+void switch_::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void switch_::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void switch_::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const switch_::position_optional& switch_::
+position () const
+{
+  return this->position_;
+}
+
+switch_::position_optional& switch_::
+position ()
+{
+  return this->position_;
+}
+
+void switch_::
+position (const position_type& x)
+{
+  this->position_.set (x);
+}
+
+void switch_::
+position (const position_optional& x)
+{
+  this->position_ = x;
+}
+
+void switch_::
+position (::std::unique_ptr< position_type > x)
+{
+  this->position_.set (std::move (x));
+}
+
+
+// laneLink
+// 
+
+const laneLink::userData_sequence& laneLink::
+userData () const
+{
+  return this->userData_;
+}
+
+laneLink::userData_sequence& laneLink::
+userData ()
+{
+  return this->userData_;
+}
+
+void laneLink::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const laneLink::include_sequence& laneLink::
+include () const
+{
+  return this->include_;
+}
+
+laneLink::include_sequence& laneLink::
+include ()
+{
+  return this->include_;
+}
+
+void laneLink::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const laneLink::from_optional& laneLink::
+from () const
+{
+  return this->from_;
+}
+
+laneLink::from_optional& laneLink::
+from ()
+{
+  return this->from_;
+}
+
+void laneLink::
+from (const from_type& x)
+{
+  this->from_.set (x);
+}
+
+void laneLink::
+from (const from_optional& x)
+{
+  this->from_ = x;
+}
+
+const laneLink::to_optional& laneLink::
+to () const
+{
+  return this->to_;
+}
+
+laneLink::to_optional& laneLink::
+to ()
+{
+  return this->to_;
+}
+
+void laneLink::
+to (const to_type& x)
+{
+  this->to_.set (x);
+}
+
+void laneLink::
+to (const to_optional& x)
+{
+  this->to_ = x;
+}
+
+
+// segment
+// 
+
+const segment::userData_sequence& segment::
+userData () const
+{
+  return this->userData_;
+}
+
+segment::userData_sequence& segment::
+userData ()
+{
+  return this->userData_;
+}
+
+void segment::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const segment::include_sequence& segment::
+include () const
+{
+  return this->include_;
+}
+
+segment::include_sequence& segment::
+include ()
+{
+  return this->include_;
+}
+
+void segment::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const segment::roadId_optional& segment::
+roadId () const
+{
+  return this->roadId_;
+}
+
+segment::roadId_optional& segment::
+roadId ()
+{
+  return this->roadId_;
+}
+
+void segment::
+roadId (const roadId_type& x)
+{
+  this->roadId_.set (x);
+}
+
+void segment::
+roadId (const roadId_optional& x)
+{
+  this->roadId_ = x;
+}
+
+void segment::
+roadId (::std::unique_ptr< roadId_type > x)
+{
+  this->roadId_.set (std::move (x));
+}
+
+const segment::sStart_optional& segment::
+sStart () const
+{
+  return this->sStart_;
+}
+
+segment::sStart_optional& segment::
+sStart ()
+{
+  return this->sStart_;
+}
+
+void segment::
+sStart (const sStart_type& x)
+{
+  this->sStart_.set (x);
+}
+
+void segment::
+sStart (const sStart_optional& x)
+{
+  this->sStart_ = x;
+}
+
+const segment::sEnd_optional& segment::
+sEnd () const
+{
+  return this->sEnd_;
+}
+
+segment::sEnd_optional& segment::
+sEnd ()
+{
+  return this->sEnd_;
+}
+
+void segment::
+sEnd (const sEnd_type& x)
+{
+  this->sEnd_.set (x);
+}
+
+void segment::
+sEnd (const sEnd_optional& x)
+{
+  this->sEnd_ = x;
+}
+
+const segment::side_optional& segment::
+side () const
+{
+  return this->side_;
+}
+
+segment::side_optional& segment::
+side ()
+{
+  return this->side_;
+}
+
+void segment::
+side (const side_type& x)
+{
+  this->side_.set (x);
+}
+
+void segment::
+side (const side_optional& x)
+{
+  this->side_ = x;
+}
+
+void segment::
+side (::std::unique_ptr< side_type > x)
+{
+  this->side_.set (std::move (x));
+}
+
+
+// line1
+// 
+
+const line1::userData_sequence& line1::
+userData () const
+{
+  return this->userData_;
+}
+
+line1::userData_sequence& line1::
+userData ()
+{
+  return this->userData_;
+}
+
+void line1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const line1::include_sequence& line1::
+include () const
+{
+  return this->include_;
+}
+
+line1::include_sequence& line1::
+include ()
+{
+  return this->include_;
+}
+
+void line1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// spiral
+// 
+
+const spiral::userData_sequence& spiral::
+userData () const
+{
+  return this->userData_;
+}
+
+spiral::userData_sequence& spiral::
+userData ()
+{
+  return this->userData_;
+}
+
+void spiral::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const spiral::include_sequence& spiral::
+include () const
+{
+  return this->include_;
+}
+
+spiral::include_sequence& spiral::
+include ()
+{
+  return this->include_;
+}
+
+void spiral::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const spiral::curvStart_optional& spiral::
+curvStart () const
+{
+  return this->curvStart_;
+}
+
+spiral::curvStart_optional& spiral::
+curvStart ()
+{
+  return this->curvStart_;
+}
+
+void spiral::
+curvStart (const curvStart_type& x)
+{
+  this->curvStart_.set (x);
+}
+
+void spiral::
+curvStart (const curvStart_optional& x)
+{
+  this->curvStart_ = x;
+}
+
+const spiral::curvEnd_optional& spiral::
+curvEnd () const
+{
+  return this->curvEnd_;
+}
+
+spiral::curvEnd_optional& spiral::
+curvEnd ()
+{
+  return this->curvEnd_;
+}
+
+void spiral::
+curvEnd (const curvEnd_type& x)
+{
+  this->curvEnd_.set (x);
+}
+
+void spiral::
+curvEnd (const curvEnd_optional& x)
+{
+  this->curvEnd_ = x;
+}
+
+
+// arc
+// 
+
+const arc::userData_sequence& arc::
+userData () const
+{
+  return this->userData_;
+}
+
+arc::userData_sequence& arc::
+userData ()
+{
+  return this->userData_;
+}
+
+void arc::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const arc::include_sequence& arc::
+include () const
+{
+  return this->include_;
+}
+
+arc::include_sequence& arc::
+include ()
+{
+  return this->include_;
+}
+
+void arc::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const arc::curvature_optional& arc::
+curvature () const
+{
+  return this->curvature_;
+}
+
+arc::curvature_optional& arc::
+curvature ()
+{
+  return this->curvature_;
+}
+
+void arc::
+curvature (const curvature_type& x)
+{
+  this->curvature_.set (x);
+}
+
+void arc::
+curvature (const curvature_optional& x)
+{
+  this->curvature_ = x;
+}
+
+
+// poly3
+// 
+
+const poly3::userData_sequence& poly3::
+userData () const
+{
+  return this->userData_;
+}
+
+poly3::userData_sequence& poly3::
+userData ()
+{
+  return this->userData_;
+}
+
+void poly3::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const poly3::include_sequence& poly3::
+include () const
+{
+  return this->include_;
+}
+
+poly3::include_sequence& poly3::
+include ()
+{
+  return this->include_;
+}
+
+void poly3::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const poly3::a_optional& poly3::
+a () const
+{
+  return this->a_;
+}
+
+poly3::a_optional& poly3::
+a ()
+{
+  return this->a_;
+}
+
+void poly3::
+a (const a_type& x)
+{
+  this->a_.set (x);
+}
+
+void poly3::
+a (const a_optional& x)
+{
+  this->a_ = x;
+}
+
+const poly3::b_optional& poly3::
+b () const
+{
+  return this->b_;
+}
+
+poly3::b_optional& poly3::
+b ()
+{
+  return this->b_;
+}
+
+void poly3::
+b (const b_type& x)
+{
+  this->b_.set (x);
+}
+
+void poly3::
+b (const b_optional& x)
+{
+  this->b_ = x;
+}
+
+const poly3::c_optional& poly3::
+c () const
+{
+  return this->c_;
+}
+
+poly3::c_optional& poly3::
+c ()
+{
+  return this->c_;
+}
+
+void poly3::
+c (const c_type& x)
+{
+  this->c_.set (x);
+}
+
+void poly3::
+c (const c_optional& x)
+{
+  this->c_ = x;
+}
+
+const poly3::d_optional& poly3::
+d () const
+{
+  return this->d_;
+}
+
+poly3::d_optional& poly3::
+d ()
+{
+  return this->d_;
+}
+
+void poly3::
+d (const d_type& x)
+{
+  this->d_.set (x);
+}
+
+void poly3::
+d (const d_optional& x)
+{
+  this->d_ = x;
+}
+
+
+// paramPoly3
+// 
+
+const paramPoly3::userData_sequence& paramPoly3::
+userData () const
+{
+  return this->userData_;
+}
+
+paramPoly3::userData_sequence& paramPoly3::
+userData ()
+{
+  return this->userData_;
+}
+
+void paramPoly3::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const paramPoly3::include_sequence& paramPoly3::
+include () const
+{
+  return this->include_;
+}
+
+paramPoly3::include_sequence& paramPoly3::
+include ()
+{
+  return this->include_;
+}
+
+void paramPoly3::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const paramPoly3::aU_optional& paramPoly3::
+aU () const
+{
+  return this->aU_;
+}
+
+paramPoly3::aU_optional& paramPoly3::
+aU ()
+{
+  return this->aU_;
+}
+
+void paramPoly3::
+aU (const aU_type& x)
+{
+  this->aU_.set (x);
+}
+
+void paramPoly3::
+aU (const aU_optional& x)
+{
+  this->aU_ = x;
+}
+
+const paramPoly3::bU_optional& paramPoly3::
+bU () const
+{
+  return this->bU_;
+}
+
+paramPoly3::bU_optional& paramPoly3::
+bU ()
+{
+  return this->bU_;
+}
+
+void paramPoly3::
+bU (const bU_type& x)
+{
+  this->bU_.set (x);
+}
+
+void paramPoly3::
+bU (const bU_optional& x)
+{
+  this->bU_ = x;
+}
+
+const paramPoly3::cU_optional& paramPoly3::
+cU () const
+{
+  return this->cU_;
+}
+
+paramPoly3::cU_optional& paramPoly3::
+cU ()
+{
+  return this->cU_;
+}
+
+void paramPoly3::
+cU (const cU_type& x)
+{
+  this->cU_.set (x);
+}
+
+void paramPoly3::
+cU (const cU_optional& x)
+{
+  this->cU_ = x;
+}
+
+const paramPoly3::dU_optional& paramPoly3::
+dU () const
+{
+  return this->dU_;
+}
+
+paramPoly3::dU_optional& paramPoly3::
+dU ()
+{
+  return this->dU_;
+}
+
+void paramPoly3::
+dU (const dU_type& x)
+{
+  this->dU_.set (x);
+}
+
+void paramPoly3::
+dU (const dU_optional& x)
+{
+  this->dU_ = x;
+}
+
+const paramPoly3::aV_optional& paramPoly3::
+aV () const
+{
+  return this->aV_;
+}
+
+paramPoly3::aV_optional& paramPoly3::
+aV ()
+{
+  return this->aV_;
+}
+
+void paramPoly3::
+aV (const aV_type& x)
+{
+  this->aV_.set (x);
+}
+
+void paramPoly3::
+aV (const aV_optional& x)
+{
+  this->aV_ = x;
+}
+
+const paramPoly3::bV_optional& paramPoly3::
+bV () const
+{
+  return this->bV_;
+}
+
+paramPoly3::bV_optional& paramPoly3::
+bV ()
+{
+  return this->bV_;
+}
+
+void paramPoly3::
+bV (const bV_type& x)
+{
+  this->bV_.set (x);
+}
+
+void paramPoly3::
+bV (const bV_optional& x)
+{
+  this->bV_ = x;
+}
+
+const paramPoly3::cV_optional& paramPoly3::
+cV () const
+{
+  return this->cV_;
+}
+
+paramPoly3::cV_optional& paramPoly3::
+cV ()
+{
+  return this->cV_;
+}
+
+void paramPoly3::
+cV (const cV_type& x)
+{
+  this->cV_.set (x);
+}
+
+void paramPoly3::
+cV (const cV_optional& x)
+{
+  this->cV_ = x;
+}
+
+const paramPoly3::dV_optional& paramPoly3::
+dV () const
+{
+  return this->dV_;
+}
+
+paramPoly3::dV_optional& paramPoly3::
+dV ()
+{
+  return this->dV_;
+}
+
+void paramPoly3::
+dV (const dV_type& x)
+{
+  this->dV_.set (x);
+}
+
+void paramPoly3::
+dV (const dV_optional& x)
+{
+  this->dV_ = x;
+}
+
+const paramPoly3::pRange_optional& paramPoly3::
+pRange () const
+{
+  return this->pRange_;
+}
+
+paramPoly3::pRange_optional& paramPoly3::
+pRange ()
+{
+  return this->pRange_;
+}
+
+void paramPoly3::
+pRange (const pRange_type& x)
+{
+  this->pRange_.set (x);
+}
+
+void paramPoly3::
+pRange (const pRange_optional& x)
+{
+  this->pRange_ = x;
+}
+
+void paramPoly3::
+pRange (::std::unique_ptr< pRange_type > x)
+{
+  this->pRange_.set (std::move (x));
+}
+
+
+// left
+// 
+
+const left::lane_sequence& left::
+lane () const
+{
+  return this->lane_;
+}
+
+left::lane_sequence& left::
+lane ()
+{
+  return this->lane_;
+}
+
+void left::
+lane (const lane_sequence& s)
+{
+  this->lane_ = s;
+}
+
+const left::userData_sequence& left::
+userData () const
+{
+  return this->userData_;
+}
+
+left::userData_sequence& left::
+userData ()
+{
+  return this->userData_;
+}
+
+void left::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const left::include_sequence& left::
+include () const
+{
+  return this->include_;
+}
+
+left::include_sequence& left::
+include ()
+{
+  return this->include_;
+}
+
+void left::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// center
+// 
+
+const center::lane_optional& center::
+lane () const
+{
+  return this->lane_;
+}
+
+center::lane_optional& center::
+lane ()
+{
+  return this->lane_;
+}
+
+void center::
+lane (const lane_type& x)
+{
+  this->lane_.set (x);
+}
+
+void center::
+lane (const lane_optional& x)
+{
+  this->lane_ = x;
+}
+
+void center::
+lane (::std::unique_ptr< lane_type > x)
+{
+  this->lane_.set (std::move (x));
+}
+
+const center::userData_sequence& center::
+userData () const
+{
+  return this->userData_;
+}
+
+center::userData_sequence& center::
+userData ()
+{
+  return this->userData_;
+}
+
+void center::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const center::include_sequence& center::
+include () const
+{
+  return this->include_;
+}
+
+center::include_sequence& center::
+include ()
+{
+  return this->include_;
+}
+
+void center::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// right
+// 
+
+const right::lane_sequence& right::
+lane () const
+{
+  return this->lane_;
+}
+
+right::lane_sequence& right::
+lane ()
+{
+  return this->lane_;
+}
+
+void right::
+lane (const lane_sequence& s)
+{
+  this->lane_ = s;
+}
+
+const right::userData_sequence& right::
+userData () const
+{
+  return this->userData_;
+}
+
+right::userData_sequence& right::
+userData ()
+{
+  return this->userData_;
+}
+
+void right::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const right::include_sequence& right::
+include () const
+{
+  return this->include_;
+}
+
+right::include_sequence& right::
+include ()
+{
+  return this->include_;
+}
+
+void right::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// repeat
+// 
+
+const repeat::userData_sequence& repeat::
+userData () const
+{
+  return this->userData_;
+}
+
+repeat::userData_sequence& repeat::
+userData ()
+{
+  return this->userData_;
+}
+
+void repeat::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const repeat::include_sequence& repeat::
+include () const
+{
+  return this->include_;
+}
+
+repeat::include_sequence& repeat::
+include ()
+{
+  return this->include_;
+}
+
+void repeat::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const repeat::s_optional& repeat::
+s () const
+{
+  return this->s_;
+}
+
+repeat::s_optional& repeat::
+s ()
+{
+  return this->s_;
+}
+
+void repeat::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void repeat::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const repeat::length_optional& repeat::
+length () const
+{
+  return this->length_;
+}
+
+repeat::length_optional& repeat::
+length ()
+{
+  return this->length_;
+}
+
+void repeat::
+length (const length_type& x)
+{
+  this->length_.set (x);
+}
+
+void repeat::
+length (const length_optional& x)
+{
+  this->length_ = x;
+}
+
+const repeat::distance_optional& repeat::
+distance () const
+{
+  return this->distance_;
+}
+
+repeat::distance_optional& repeat::
+distance ()
+{
+  return this->distance_;
+}
+
+void repeat::
+distance (const distance_type& x)
+{
+  this->distance_.set (x);
+}
+
+void repeat::
+distance (const distance_optional& x)
+{
+  this->distance_ = x;
+}
+
+const repeat::tStart_optional& repeat::
+tStart () const
+{
+  return this->tStart_;
+}
+
+repeat::tStart_optional& repeat::
+tStart ()
+{
+  return this->tStart_;
+}
+
+void repeat::
+tStart (const tStart_type& x)
+{
+  this->tStart_.set (x);
+}
+
+void repeat::
+tStart (const tStart_optional& x)
+{
+  this->tStart_ = x;
+}
+
+const repeat::tEnd_optional& repeat::
+tEnd () const
+{
+  return this->tEnd_;
+}
+
+repeat::tEnd_optional& repeat::
+tEnd ()
+{
+  return this->tEnd_;
+}
+
+void repeat::
+tEnd (const tEnd_type& x)
+{
+  this->tEnd_.set (x);
+}
+
+void repeat::
+tEnd (const tEnd_optional& x)
+{
+  this->tEnd_ = x;
+}
+
+const repeat::widthStart_optional& repeat::
+widthStart () const
+{
+  return this->widthStart_;
+}
+
+repeat::widthStart_optional& repeat::
+widthStart ()
+{
+  return this->widthStart_;
+}
+
+void repeat::
+widthStart (const widthStart_type& x)
+{
+  this->widthStart_.set (x);
+}
+
+void repeat::
+widthStart (const widthStart_optional& x)
+{
+  this->widthStart_ = x;
+}
+
+const repeat::widthEnd_optional& repeat::
+widthEnd () const
+{
+  return this->widthEnd_;
+}
+
+repeat::widthEnd_optional& repeat::
+widthEnd ()
+{
+  return this->widthEnd_;
+}
+
+void repeat::
+widthEnd (const widthEnd_type& x)
+{
+  this->widthEnd_.set (x);
+}
+
+void repeat::
+widthEnd (const widthEnd_optional& x)
+{
+  this->widthEnd_ = x;
+}
+
+const repeat::heightStart_optional& repeat::
+heightStart () const
+{
+  return this->heightStart_;
+}
+
+repeat::heightStart_optional& repeat::
+heightStart ()
+{
+  return this->heightStart_;
+}
+
+void repeat::
+heightStart (const heightStart_type& x)
+{
+  this->heightStart_.set (x);
+}
+
+void repeat::
+heightStart (const heightStart_optional& x)
+{
+  this->heightStart_ = x;
+}
+
+const repeat::heightEnd_optional& repeat::
+heightEnd () const
+{
+  return this->heightEnd_;
+}
+
+repeat::heightEnd_optional& repeat::
+heightEnd ()
+{
+  return this->heightEnd_;
+}
+
+void repeat::
+heightEnd (const heightEnd_type& x)
+{
+  this->heightEnd_.set (x);
+}
+
+void repeat::
+heightEnd (const heightEnd_optional& x)
+{
+  this->heightEnd_ = x;
+}
+
+const repeat::zOffsetStart_optional& repeat::
+zOffsetStart () const
+{
+  return this->zOffsetStart_;
+}
+
+repeat::zOffsetStart_optional& repeat::
+zOffsetStart ()
+{
+  return this->zOffsetStart_;
+}
+
+void repeat::
+zOffsetStart (const zOffsetStart_type& x)
+{
+  this->zOffsetStart_.set (x);
+}
+
+void repeat::
+zOffsetStart (const zOffsetStart_optional& x)
+{
+  this->zOffsetStart_ = x;
+}
+
+const repeat::zOffsetEnd_optional& repeat::
+zOffsetEnd () const
+{
+  return this->zOffsetEnd_;
+}
+
+repeat::zOffsetEnd_optional& repeat::
+zOffsetEnd ()
+{
+  return this->zOffsetEnd_;
+}
+
+void repeat::
+zOffsetEnd (const zOffsetEnd_type& x)
+{
+  this->zOffsetEnd_.set (x);
+}
+
+void repeat::
+zOffsetEnd (const zOffsetEnd_optional& x)
+{
+  this->zOffsetEnd_ = x;
+}
+
+
+// outline
+// 
+
+const outline::cornerRoad_sequence& outline::
+cornerRoad () const
+{
+  return this->cornerRoad_;
+}
+
+outline::cornerRoad_sequence& outline::
+cornerRoad ()
+{
+  return this->cornerRoad_;
+}
+
+void outline::
+cornerRoad (const cornerRoad_sequence& s)
+{
+  this->cornerRoad_ = s;
+}
+
+const outline::cornerLocal_sequence& outline::
+cornerLocal () const
+{
+  return this->cornerLocal_;
+}
+
+outline::cornerLocal_sequence& outline::
+cornerLocal ()
+{
+  return this->cornerLocal_;
+}
+
+void outline::
+cornerLocal (const cornerLocal_sequence& s)
+{
+  this->cornerLocal_ = s;
+}
+
+const outline::userData_sequence& outline::
+userData () const
+{
+  return this->userData_;
+}
+
+outline::userData_sequence& outline::
+userData ()
+{
+  return this->userData_;
+}
+
+void outline::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const outline::include_sequence& outline::
+include () const
+{
+  return this->include_;
+}
+
+outline::include_sequence& outline::
+include ()
+{
+  return this->include_;
+}
+
+void outline::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+
+// material1
+// 
+
+const material1::userData_sequence& material1::
+userData () const
+{
+  return this->userData_;
+}
+
+material1::userData_sequence& material1::
+userData ()
+{
+  return this->userData_;
+}
+
+void material1::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const material1::include_sequence& material1::
+include () const
+{
+  return this->include_;
+}
+
+material1::include_sequence& material1::
+include ()
+{
+  return this->include_;
+}
+
+void material1::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const material1::surface_optional& material1::
+surface () const
+{
+  return this->surface_;
+}
+
+material1::surface_optional& material1::
+surface ()
+{
+  return this->surface_;
+}
+
+void material1::
+surface (const surface_type& x)
+{
+  this->surface_.set (x);
+}
+
+void material1::
+surface (const surface_optional& x)
+{
+  this->surface_ = x;
+}
+
+void material1::
+surface (::std::unique_ptr< surface_type > x)
+{
+  this->surface_.set (std::move (x));
+}
+
+const material1::friction_optional& material1::
+friction () const
+{
+  return this->friction_;
+}
+
+material1::friction_optional& material1::
+friction ()
+{
+  return this->friction_;
+}
+
+void material1::
+friction (const friction_type& x)
+{
+  this->friction_.set (x);
+}
+
+void material1::
+friction (const friction_optional& x)
+{
+  this->friction_ = x;
+}
+
+const material1::roughness_optional& material1::
+roughness () const
+{
+  return this->roughness_;
+}
+
+material1::roughness_optional& material1::
+roughness ()
+{
+  return this->roughness_;
+}
+
+void material1::
+roughness (const roughness_type& x)
+{
+  this->roughness_.set (x);
+}
+
+void material1::
+roughness (const roughness_optional& x)
+{
+  this->roughness_ = x;
+}
+
+
+// dependency
+// 
+
+const dependency::userData_sequence& dependency::
+userData () const
+{
+  return this->userData_;
+}
+
+dependency::userData_sequence& dependency::
+userData ()
+{
+  return this->userData_;
+}
+
+void dependency::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const dependency::include_sequence& dependency::
+include () const
+{
+  return this->include_;
+}
+
+dependency::include_sequence& dependency::
+include ()
+{
+  return this->include_;
+}
+
+void dependency::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const dependency::id_optional& dependency::
+id () const
+{
+  return this->id_;
+}
+
+dependency::id_optional& dependency::
+id ()
+{
+  return this->id_;
+}
+
+void dependency::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void dependency::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void dependency::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const dependency::type_optional& dependency::
+type () const
+{
+  return this->type_;
+}
+
+dependency::type_optional& dependency::
+type ()
+{
+  return this->type_;
+}
+
+void dependency::
+type (const type_type& x)
+{
+  this->type_.set (x);
+}
+
+void dependency::
+type (const type_optional& x)
+{
+  this->type_ = x;
+}
+
+void dependency::
+type (::std::unique_ptr< type_type > x)
+{
+  this->type_.set (std::move (x));
+}
+
+
+// mainTrack
+// 
+
+const mainTrack::id_optional& mainTrack::
+id () const
+{
+  return this->id_;
+}
+
+mainTrack::id_optional& mainTrack::
+id ()
+{
+  return this->id_;
+}
+
+void mainTrack::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void mainTrack::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void mainTrack::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const mainTrack::s_optional& mainTrack::
+s () const
+{
+  return this->s_;
+}
+
+mainTrack::s_optional& mainTrack::
+s ()
+{
+  return this->s_;
+}
+
+void mainTrack::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void mainTrack::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const mainTrack::dir_optional& mainTrack::
+dir () const
+{
+  return this->dir_;
+}
+
+mainTrack::dir_optional& mainTrack::
+dir ()
+{
+  return this->dir_;
+}
+
+void mainTrack::
+dir (const dir_type& x)
+{
+  this->dir_.set (x);
+}
+
+void mainTrack::
+dir (const dir_optional& x)
+{
+  this->dir_ = x;
+}
+
+void mainTrack::
+dir (::std::unique_ptr< dir_type > x)
+{
+  this->dir_.set (std::move (x));
+}
+
+
+// sideTrack
+// 
+
+const sideTrack::id_optional& sideTrack::
+id () const
+{
+  return this->id_;
+}
+
+sideTrack::id_optional& sideTrack::
+id ()
+{
+  return this->id_;
+}
+
+void sideTrack::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void sideTrack::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void sideTrack::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+const sideTrack::s_optional& sideTrack::
+s () const
+{
+  return this->s_;
+}
+
+sideTrack::s_optional& sideTrack::
+s ()
+{
+  return this->s_;
+}
+
+void sideTrack::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void sideTrack::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const sideTrack::dir_optional& sideTrack::
+dir () const
+{
+  return this->dir_;
+}
+
+sideTrack::dir_optional& sideTrack::
+dir ()
+{
+  return this->dir_;
+}
+
+void sideTrack::
+dir (const dir_type& x)
+{
+  this->dir_.set (x);
+}
+
+void sideTrack::
+dir (const dir_optional& x)
+{
+  this->dir_ = x;
+}
+
+void sideTrack::
+dir (::std::unique_ptr< dir_type > x)
+{
+  this->dir_.set (std::move (x));
+}
+
+
+// partner
+// 
+
+const partner::name_optional& partner::
+name () const
+{
+  return this->name_;
+}
+
+partner::name_optional& partner::
+name ()
+{
+  return this->name_;
+}
+
+void partner::
+name (const name_type& x)
+{
+  this->name_.set (x);
+}
+
+void partner::
+name (const name_optional& x)
+{
+  this->name_ = x;
+}
+
+void partner::
+name (::std::unique_ptr< name_type > x)
+{
+  this->name_.set (std::move (x));
+}
+
+const partner::id_optional& partner::
+id () const
+{
+  return this->id_;
+}
+
+partner::id_optional& partner::
+id ()
+{
+  return this->id_;
+}
+
+void partner::
+id (const id_type& x)
+{
+  this->id_.set (x);
+}
+
+void partner::
+id (const id_optional& x)
+{
+  this->id_ = x;
+}
+
+void partner::
+id (::std::unique_ptr< id_type > x)
+{
+  this->id_.set (std::move (x));
+}
+
+
+// cornerRoad
+// 
+
+const cornerRoad::userData_sequence& cornerRoad::
+userData () const
+{
+  return this->userData_;
+}
+
+cornerRoad::userData_sequence& cornerRoad::
+userData ()
+{
+  return this->userData_;
+}
+
+void cornerRoad::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const cornerRoad::include_sequence& cornerRoad::
+include () const
+{
+  return this->include_;
+}
+
+cornerRoad::include_sequence& cornerRoad::
+include ()
+{
+  return this->include_;
+}
+
+void cornerRoad::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const cornerRoad::s_optional& cornerRoad::
+s () const
+{
+  return this->s_;
+}
+
+cornerRoad::s_optional& cornerRoad::
+s ()
+{
+  return this->s_;
+}
+
+void cornerRoad::
+s (const s_type& x)
+{
+  this->s_.set (x);
+}
+
+void cornerRoad::
+s (const s_optional& x)
+{
+  this->s_ = x;
+}
+
+const cornerRoad::t_optional& cornerRoad::
+t () const
+{
+  return this->t_;
+}
+
+cornerRoad::t_optional& cornerRoad::
+t ()
+{
+  return this->t_;
+}
+
+void cornerRoad::
+t (const t_type& x)
+{
+  this->t_.set (x);
+}
+
+void cornerRoad::
+t (const t_optional& x)
+{
+  this->t_ = x;
+}
+
+const cornerRoad::dz_optional& cornerRoad::
+dz () const
+{
+  return this->dz_;
+}
+
+cornerRoad::dz_optional& cornerRoad::
+dz ()
+{
+  return this->dz_;
+}
+
+void cornerRoad::
+dz (const dz_type& x)
+{
+  this->dz_.set (x);
+}
+
+void cornerRoad::
+dz (const dz_optional& x)
+{
+  this->dz_ = x;
+}
+
+const cornerRoad::height_optional& cornerRoad::
+height () const
+{
+  return this->height_;
+}
+
+cornerRoad::height_optional& cornerRoad::
+height ()
+{
+  return this->height_;
+}
+
+void cornerRoad::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void cornerRoad::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+
+// cornerLocal
+// 
+
+const cornerLocal::userData_sequence& cornerLocal::
+userData () const
+{
+  return this->userData_;
+}
+
+cornerLocal::userData_sequence& cornerLocal::
+userData ()
+{
+  return this->userData_;
+}
+
+void cornerLocal::
+userData (const userData_sequence& s)
+{
+  this->userData_ = s;
+}
+
+const cornerLocal::include_sequence& cornerLocal::
+include () const
+{
+  return this->include_;
+}
+
+cornerLocal::include_sequence& cornerLocal::
+include ()
+{
+  return this->include_;
+}
+
+void cornerLocal::
+include (const include_sequence& s)
+{
+  this->include_ = s;
+}
+
+const cornerLocal::u_optional& cornerLocal::
+u () const
+{
+  return this->u_;
+}
+
+cornerLocal::u_optional& cornerLocal::
+u ()
+{
+  return this->u_;
+}
+
+void cornerLocal::
+u (const u_type& x)
+{
+  this->u_.set (x);
+}
+
+void cornerLocal::
+u (const u_optional& x)
+{
+  this->u_ = x;
+}
+
+const cornerLocal::v_optional& cornerLocal::
+v () const
+{
+  return this->v_;
+}
+
+cornerLocal::v_optional& cornerLocal::
+v ()
+{
+  return this->v_;
+}
+
+void cornerLocal::
+v (const v_type& x)
+{
+  this->v_.set (x);
+}
+
+void cornerLocal::
+v (const v_optional& x)
+{
+  this->v_ = x;
+}
+
+const cornerLocal::z_optional& cornerLocal::
+z () const
+{
+  return this->z_;
+}
+
+cornerLocal::z_optional& cornerLocal::
+z ()
+{
+  return this->z_;
+}
+
+void cornerLocal::
+z (const z_type& x)
+{
+  this->z_.set (x);
+}
+
+void cornerLocal::
+z (const z_optional& x)
+{
+  this->z_ = x;
+}
+
+const cornerLocal::height_optional& cornerLocal::
+height () const
+{
+  return this->height_;
+}
+
+cornerLocal::height_optional& cornerLocal::
+height ()
+{
+  return this->height_;
+}
+
+void cornerLocal::
+height (const height_type& x)
+{
+  this->height_.set (x);
+}
+
+void cornerLocal::
+height (const height_optional& x)
+{
+  this->height_ = x;
+}
+
+
+#include <xsd/cxx/xml/dom/parsing-source.hxx>
+
+// elementType
+//
+
+elementType::
+elementType (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_elementType_convert ();
+}
+
+elementType::
+elementType (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_elementType_convert ();
+}
+
+elementType::
+elementType (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_elementType_convert ();
+}
+
+elementType* elementType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class elementType (*this, f, c);
+}
+
+elementType::value elementType::
+_xsd_elementType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_elementType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_elementType_indexes_,
+                    _xsd_elementType_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_elementType_indexes_ + 2 || _xsd_elementType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const elementType::
+_xsd_elementType_literals_[2] =
+{
+  "road",
+  "junction"
+};
+
+const elementType::value elementType::
+_xsd_elementType_indexes_[2] =
+{
+  ::elementType::junction,
+  ::elementType::road
+};
+
+// max
+//
+
+max::
+max (const ::xercesc::DOMElement& e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+}
+
+max::
+max (const ::xercesc::DOMAttr& a,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+}
+
+max::
+max (const ::std::string& s,
+     const ::xercesc::DOMElement* e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+}
+
+max* max::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class max (*this, f, c);
+}
+
+// contactPoint
+//
+
+contactPoint::
+contactPoint (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_contactPoint_convert ();
+}
+
+contactPoint::
+contactPoint (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_contactPoint_convert ();
+}
+
+contactPoint::
+contactPoint (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_contactPoint_convert ();
+}
+
+contactPoint* contactPoint::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class contactPoint (*this, f, c);
+}
+
+contactPoint::value contactPoint::
+_xsd_contactPoint_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_contactPoint_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_contactPoint_indexes_,
+                    _xsd_contactPoint_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_contactPoint_indexes_ + 2 || _xsd_contactPoint_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const contactPoint::
+_xsd_contactPoint_literals_[2] =
+{
+  "start",
+  "end"
+};
+
+const contactPoint::value contactPoint::
+_xsd_contactPoint_indexes_[2] =
+{
+  ::contactPoint::end,
+  ::contactPoint::start
+};
+
+// side
+//
+
+side::
+side (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_side_convert ();
+}
+
+side::
+side (const ::xercesc::DOMAttr& a,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_side_convert ();
+}
+
+side::
+side (const ::std::string& s,
+      const ::xercesc::DOMElement* e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_side_convert ();
+}
+
+side* side::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class side (*this, f, c);
+}
+
+side::value side::
+_xsd_side_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_side_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_side_indexes_,
+                    _xsd_side_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_side_indexes_ + 2 || _xsd_side_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const side::
+_xsd_side_literals_[2] =
+{
+  "left",
+  "right"
+};
+
+const side::value side::
+_xsd_side_indexes_[2] =
+{
+  ::side::left,
+  ::side::right
+};
+
+// direction
+//
+
+direction::
+direction (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_direction_convert ();
+}
+
+direction::
+direction (const ::xercesc::DOMAttr& a,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_direction_convert ();
+}
+
+direction::
+direction (const ::std::string& s,
+           const ::xercesc::DOMElement* e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_direction_convert ();
+}
+
+direction* direction::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class direction (*this, f, c);
+}
+
+direction::value direction::
+_xsd_direction_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_direction_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_direction_indexes_,
+                    _xsd_direction_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_direction_indexes_ + 2 || _xsd_direction_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const direction::
+_xsd_direction_literals_[2] =
+{
+  "same",
+  "opposite"
+};
+
+const direction::value direction::
+_xsd_direction_indexes_[2] =
+{
+  ::direction::opposite,
+  ::direction::same
+};
+
+// roadType
+//
+
+roadType::
+roadType (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_roadType_convert ();
+}
+
+roadType::
+roadType (const ::xercesc::DOMAttr& a,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_roadType_convert ();
+}
+
+roadType::
+roadType (const ::std::string& s,
+          const ::xercesc::DOMElement* e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_roadType_convert ();
+}
+
+roadType* roadType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class roadType (*this, f, c);
+}
+
+roadType::value roadType::
+_xsd_roadType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_roadType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_roadType_indexes_,
+                    _xsd_roadType_indexes_ + 7,
+                    *this,
+                    c));
+
+  if (i == _xsd_roadType_indexes_ + 7 || _xsd_roadType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const roadType::
+_xsd_roadType_literals_[7] =
+{
+  "unknown",
+  "rural",
+  "motorway",
+  "town",
+  "lowSpeed",
+  "pedestrian",
+  "bicycle"
+};
+
+const roadType::value roadType::
+_xsd_roadType_indexes_[7] =
+{
+  ::roadType::bicycle,
+  ::roadType::lowSpeed,
+  ::roadType::motorway,
+  ::roadType::pedestrian,
+  ::roadType::rural,
+  ::roadType::town,
+  ::roadType::unknown
+};
+
+// unit
+//
+
+unit::
+unit (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_unit_convert ();
+}
+
+unit::
+unit (const ::xercesc::DOMAttr& a,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_unit_convert ();
+}
+
+unit::
+unit (const ::std::string& s,
+      const ::xercesc::DOMElement* e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_unit_convert ();
+}
+
+unit* unit::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class unit (*this, f, c);
+}
+
+unit::value unit::
+_xsd_unit_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_unit_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_unit_indexes_,
+                    _xsd_unit_indexes_ + 10,
+                    *this,
+                    c));
+
+  if (i == _xsd_unit_indexes_ + 10 || _xsd_unit_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const unit::
+_xsd_unit_literals_[10] =
+{
+  "m",
+  "km",
+  "ft",
+  "mile",
+  "m/s",
+  "mph",
+  "km/h",
+  "kg",
+  "t",
+  "%"
+};
+
+const unit::value unit::
+_xsd_unit_indexes_[10] =
+{
+  ::unit::cxx_,
+  ::unit::ft,
+  ::unit::kg,
+  ::unit::km,
+  ::unit::km_h,
+  ::unit::m,
+  ::unit::m_s,
+  ::unit::mile,
+  ::unit::mph,
+  ::unit::t
+};
+
+// pRange
+//
+
+pRange::
+pRange (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_pRange_convert ();
+}
+
+pRange::
+pRange (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_pRange_convert ();
+}
+
+pRange::
+pRange (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_pRange_convert ();
+}
+
+pRange* pRange::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class pRange (*this, f, c);
+}
+
+pRange::value pRange::
+_xsd_pRange_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_pRange_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_pRange_indexes_,
+                    _xsd_pRange_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_pRange_indexes_ + 2 || _xsd_pRange_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const pRange::
+_xsd_pRange_literals_[2] =
+{
+  "arcLength",
+  "normalized"
+};
+
+const pRange::value pRange::
+_xsd_pRange_indexes_[2] =
+{
+  ::pRange::arcLength,
+  ::pRange::normalized
+};
+
+// crossfallSide
+//
+
+crossfallSide::
+crossfallSide (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_crossfallSide_convert ();
+}
+
+crossfallSide::
+crossfallSide (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_crossfallSide_convert ();
+}
+
+crossfallSide::
+crossfallSide (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_crossfallSide_convert ();
+}
+
+crossfallSide* crossfallSide::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class crossfallSide (*this, f, c);
+}
+
+crossfallSide::value crossfallSide::
+_xsd_crossfallSide_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_crossfallSide_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_crossfallSide_indexes_,
+                    _xsd_crossfallSide_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_crossfallSide_indexes_ + 3 || _xsd_crossfallSide_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const crossfallSide::
+_xsd_crossfallSide_literals_[3] =
+{
+  "left",
+  "right",
+  "both"
+};
+
+const crossfallSide::value crossfallSide::
+_xsd_crossfallSide_indexes_[3] =
+{
+  ::crossfallSide::both,
+  ::crossfallSide::left,
+  ::crossfallSide::right
+};
+
+// singleSide
+//
+
+singleSide::
+singleSide (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_singleSide_convert ();
+}
+
+singleSide::
+singleSide (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_singleSide_convert ();
+}
+
+singleSide::
+singleSide (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_singleSide_convert ();
+}
+
+singleSide* singleSide::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class singleSide (*this, f, c);
+}
+
+singleSide::value singleSide::
+_xsd_singleSide_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_singleSide_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_singleSide_indexes_,
+                    _xsd_singleSide_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_singleSide_indexes_ + 2 || _xsd_singleSide_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const singleSide::
+_xsd_singleSide_literals_[2] =
+{
+  "true",
+  "false"
+};
+
+const singleSide::value singleSide::
+_xsd_singleSide_indexes_[2] =
+{
+  ::singleSide::false_,
+  ::singleSide::true_
+};
+
+// laneType
+//
+
+laneType::
+laneType (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_laneType_convert ();
+}
+
+laneType::
+laneType (const ::xercesc::DOMAttr& a,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_laneType_convert ();
+}
+
+laneType::
+laneType (const ::std::string& s,
+          const ::xercesc::DOMElement* e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_laneType_convert ();
+}
+
+laneType* laneType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneType (*this, f, c);
+}
+
+laneType::value laneType::
+_xsd_laneType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_laneType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_laneType_indexes_,
+                    _xsd_laneType_indexes_ + 21,
+                    *this,
+                    c));
+
+  if (i == _xsd_laneType_indexes_ + 21 || _xsd_laneType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const laneType::
+_xsd_laneType_literals_[21] =
+{
+  "none",
+  "driving",
+  "stop",
+  "shoulder",
+  "biking",
+  "sidewalk",
+  "border",
+  "restricted",
+  "parking",
+  "bidirectional",
+  "median",
+  "special1",
+  "special2",
+  "special3",
+  "roadWorks",
+  "tram",
+  "rail",
+  "entry",
+  "exit",
+  "offRamp",
+  "onRamp"
+};
+
+const laneType::value laneType::
+_xsd_laneType_indexes_[21] =
+{
+  ::laneType::bidirectional,
+  ::laneType::biking,
+  ::laneType::border,
+  ::laneType::driving,
+  ::laneType::entry,
+  ::laneType::exit,
+  ::laneType::median,
+  ::laneType::none,
+  ::laneType::offRamp,
+  ::laneType::onRamp,
+  ::laneType::parking,
+  ::laneType::rail,
+  ::laneType::restricted,
+  ::laneType::roadWorks,
+  ::laneType::shoulder,
+  ::laneType::sidewalk,
+  ::laneType::special1,
+  ::laneType::special2,
+  ::laneType::special3,
+  ::laneType::stop,
+  ::laneType::tram
+};
+
+// roadmarkType
+//
+
+roadmarkType::
+roadmarkType (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_roadmarkType_convert ();
+}
+
+roadmarkType::
+roadmarkType (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_roadmarkType_convert ();
+}
+
+roadmarkType::
+roadmarkType (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_roadmarkType_convert ();
+}
+
+roadmarkType* roadmarkType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class roadmarkType (*this, f, c);
+}
+
+roadmarkType::value roadmarkType::
+_xsd_roadmarkType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_roadmarkType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_roadmarkType_indexes_,
+                    _xsd_roadmarkType_indexes_ + 10,
+                    *this,
+                    c));
+
+  if (i == _xsd_roadmarkType_indexes_ + 10 || _xsd_roadmarkType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const roadmarkType::
+_xsd_roadmarkType_literals_[10] =
+{
+  "none",
+  "solid",
+  "broken",
+  "solid solid",
+  "solid broken",
+  "broken solid",
+  "broken broken",
+  "botts dots",
+  "grass",
+  "curb"
+};
+
+const roadmarkType::value roadmarkType::
+_xsd_roadmarkType_indexes_[10] =
+{
+  ::roadmarkType::botts_dots,
+  ::roadmarkType::broken,
+  ::roadmarkType::broken_broken,
+  ::roadmarkType::broken_solid,
+  ::roadmarkType::curb,
+  ::roadmarkType::grass,
+  ::roadmarkType::none,
+  ::roadmarkType::solid,
+  ::roadmarkType::solid_broken,
+  ::roadmarkType::solid_solid
+};
+
+// weight
+//
+
+weight::
+weight (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_weight_convert ();
+}
+
+weight::
+weight (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_weight_convert ();
+}
+
+weight::
+weight (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_weight_convert ();
+}
+
+weight* weight::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class weight (*this, f, c);
+}
+
+weight::value weight::
+_xsd_weight_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_weight_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_weight_indexes_,
+                    _xsd_weight_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_weight_indexes_ + 2 || _xsd_weight_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const weight::
+_xsd_weight_literals_[2] =
+{
+  "standard",
+  "bold"
+};
+
+const weight::value weight::
+_xsd_weight_indexes_[2] =
+{
+  ::weight::bold,
+  ::weight::standard
+};
+
+// color
+//
+
+color::
+color (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_color_convert ();
+}
+
+color::
+color (const ::xercesc::DOMAttr& a,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_color_convert ();
+}
+
+color::
+color (const ::std::string& s,
+       const ::xercesc::DOMElement* e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_color_convert ();
+}
+
+color* color::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class color (*this, f, c);
+}
+
+color::value color::
+_xsd_color_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_color_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_color_indexes_,
+                    _xsd_color_indexes_ + 6,
+                    *this,
+                    c));
+
+  if (i == _xsd_color_indexes_ + 6 || _xsd_color_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const color::
+_xsd_color_literals_[6] =
+{
+  "standard",
+  "blue",
+  "green",
+  "red",
+  "white",
+  "yellow"
+};
+
+const color::value color::
+_xsd_color_indexes_[6] =
+{
+  ::color::blue,
+  ::color::green,
+  ::color::red,
+  ::color::standard,
+  ::color::white,
+  ::color::yellow
+};
+
+// restriction
+//
+
+restriction::
+restriction (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_restriction_convert ();
+}
+
+restriction::
+restriction (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_restriction_convert ();
+}
+
+restriction::
+restriction (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_restriction_convert ();
+}
+
+restriction* restriction::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class restriction (*this, f, c);
+}
+
+restriction::value restriction::
+_xsd_restriction_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_restriction_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_restriction_indexes_,
+                    _xsd_restriction_indexes_ + 4,
+                    *this,
+                    c));
+
+  if (i == _xsd_restriction_indexes_ + 4 || _xsd_restriction_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const restriction::
+_xsd_restriction_literals_[4] =
+{
+  "simulator",
+  "autonomous traffic",
+  "pedestrian",
+  "none"
+};
+
+const restriction::value restriction::
+_xsd_restriction_indexes_[4] =
+{
+  ::restriction::autonomous_traffic,
+  ::restriction::none,
+  ::restriction::pedestrian,
+  ::restriction::simulator
+};
+
+// laneChange
+//
+
+laneChange::
+laneChange (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_laneChange_convert ();
+}
+
+laneChange::
+laneChange (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_laneChange_convert ();
+}
+
+laneChange::
+laneChange (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_laneChange_convert ();
+}
+
+laneChange* laneChange::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneChange (*this, f, c);
+}
+
+laneChange::value laneChange::
+_xsd_laneChange_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_laneChange_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_laneChange_indexes_,
+                    _xsd_laneChange_indexes_ + 4,
+                    *this,
+                    c));
+
+  if (i == _xsd_laneChange_indexes_ + 4 || _xsd_laneChange_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const laneChange::
+_xsd_laneChange_literals_[4] =
+{
+  "increase",
+  "decrease",
+  "both",
+  "none"
+};
+
+const laneChange::value laneChange::
+_xsd_laneChange_indexes_[4] =
+{
+  ::laneChange::both,
+  ::laneChange::decrease,
+  ::laneChange::increase,
+  ::laneChange::none
+};
+
+// rule
+//
+
+rule::
+rule (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_rule_convert ();
+}
+
+rule::
+rule (const ::xercesc::DOMAttr& a,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_rule_convert ();
+}
+
+rule::
+rule (const ::std::string& s,
+      const ::xercesc::DOMElement* e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_rule_convert ();
+}
+
+rule* rule::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class rule (*this, f, c);
+}
+
+rule::value rule::
+_xsd_rule_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_rule_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_rule_indexes_,
+                    _xsd_rule_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_rule_indexes_ + 3 || _xsd_rule_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const rule::
+_xsd_rule_literals_[3] =
+{
+  "no passing",
+  "caution",
+  "none"
+};
+
+const rule::value rule::
+_xsd_rule_indexes_[3] =
+{
+  ::rule::caution,
+  ::rule::no_passing,
+  ::rule::none
+};
+
+// orientation
+//
+
+orientation::
+orientation (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_orientation_convert ();
+}
+
+orientation::
+orientation (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_orientation_convert ();
+}
+
+orientation::
+orientation (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_orientation_convert ();
+}
+
+orientation* orientation::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class orientation (*this, f, c);
+}
+
+orientation::value orientation::
+_xsd_orientation_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_orientation_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_orientation_indexes_,
+                    _xsd_orientation_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_orientation_indexes_ + 3 || _xsd_orientation_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const orientation::
+_xsd_orientation_literals_[3] =
+{
+  "+",
+  "-",
+  "none"
+};
+
+const orientation::value orientation::
+_xsd_orientation_indexes_[3] =
+{
+  ::orientation::cxx_,
+  ::orientation::cxx_1,
+  ::orientation::none
+};
+
+// tunnelType
+//
+
+tunnelType::
+tunnelType (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_tunnelType_convert ();
+}
+
+tunnelType::
+tunnelType (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_tunnelType_convert ();
+}
+
+tunnelType::
+tunnelType (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_tunnelType_convert ();
+}
+
+tunnelType* tunnelType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class tunnelType (*this, f, c);
+}
+
+tunnelType::value tunnelType::
+_xsd_tunnelType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_tunnelType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_tunnelType_indexes_,
+                    _xsd_tunnelType_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_tunnelType_indexes_ + 2 || _xsd_tunnelType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const tunnelType::
+_xsd_tunnelType_literals_[2] =
+{
+  "standard",
+  "underpass"
+};
+
+const tunnelType::value tunnelType::
+_xsd_tunnelType_indexes_[2] =
+{
+  ::tunnelType::standard,
+  ::tunnelType::underpass
+};
+
+// bridgeType
+//
+
+bridgeType::
+bridgeType (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_bridgeType_convert ();
+}
+
+bridgeType::
+bridgeType (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_bridgeType_convert ();
+}
+
+bridgeType::
+bridgeType (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_bridgeType_convert ();
+}
+
+bridgeType* bridgeType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class bridgeType (*this, f, c);
+}
+
+bridgeType::value bridgeType::
+_xsd_bridgeType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_bridgeType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_bridgeType_indexes_,
+                    _xsd_bridgeType_indexes_ + 4,
+                    *this,
+                    c));
+
+  if (i == _xsd_bridgeType_indexes_ + 4 || _xsd_bridgeType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const bridgeType::
+_xsd_bridgeType_literals_[4] =
+{
+  "concrete",
+  "steel",
+  "brick",
+  "wood"
+};
+
+const bridgeType::value bridgeType::
+_xsd_bridgeType_indexes_[4] =
+{
+  ::bridgeType::brick,
+  ::bridgeType::concrete,
+  ::bridgeType::steel,
+  ::bridgeType::wood
+};
+
+// parkingSpace_access
+//
+
+parkingSpace_access::
+parkingSpace_access (const ::xercesc::DOMElement& e,
+                     ::xml_schema::flags f,
+                     ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_parkingSpace_access_convert ();
+}
+
+parkingSpace_access::
+parkingSpace_access (const ::xercesc::DOMAttr& a,
+                     ::xml_schema::flags f,
+                     ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_parkingSpace_access_convert ();
+}
+
+parkingSpace_access::
+parkingSpace_access (const ::std::string& s,
+                     const ::xercesc::DOMElement* e,
+                     ::xml_schema::flags f,
+                     ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_parkingSpace_access_convert ();
+}
+
+parkingSpace_access* parkingSpace_access::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class parkingSpace_access (*this, f, c);
+}
+
+parkingSpace_access::value parkingSpace_access::
+_xsd_parkingSpace_access_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_parkingSpace_access_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_parkingSpace_access_indexes_,
+                    _xsd_parkingSpace_access_indexes_ + 8,
+                    *this,
+                    c));
+
+  if (i == _xsd_parkingSpace_access_indexes_ + 8 || _xsd_parkingSpace_access_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const parkingSpace_access::
+_xsd_parkingSpace_access_literals_[8] =
+{
+  "all",
+  "car",
+  "women",
+  "handicapped",
+  "bus",
+  "truck",
+  "electric",
+  "residents"
+};
+
+const parkingSpace_access::value parkingSpace_access::
+_xsd_parkingSpace_access_indexes_[8] =
+{
+  ::parkingSpace_access::all,
+  ::parkingSpace_access::bus,
+  ::parkingSpace_access::car,
+  ::parkingSpace_access::electric,
+  ::parkingSpace_access::handicapped,
+  ::parkingSpace_access::residents,
+  ::parkingSpace_access::truck,
+  ::parkingSpace_access::women
+};
+
+// parkingSpacemarkingSide
+//
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const ::xercesc::DOMElement& e,
+                         ::xml_schema::flags f,
+                         ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_parkingSpacemarkingSide_convert ();
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const ::xercesc::DOMAttr& a,
+                         ::xml_schema::flags f,
+                         ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_parkingSpacemarkingSide_convert ();
+}
+
+parkingSpacemarkingSide::
+parkingSpacemarkingSide (const ::std::string& s,
+                         const ::xercesc::DOMElement* e,
+                         ::xml_schema::flags f,
+                         ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_parkingSpacemarkingSide_convert ();
+}
+
+parkingSpacemarkingSide* parkingSpacemarkingSide::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class parkingSpacemarkingSide (*this, f, c);
+}
+
+parkingSpacemarkingSide::value parkingSpacemarkingSide::
+_xsd_parkingSpacemarkingSide_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_parkingSpacemarkingSide_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_parkingSpacemarkingSide_indexes_,
+                    _xsd_parkingSpacemarkingSide_indexes_ + 4,
+                    *this,
+                    c));
+
+  if (i == _xsd_parkingSpacemarkingSide_indexes_ + 4 || _xsd_parkingSpacemarkingSide_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const parkingSpacemarkingSide::
+_xsd_parkingSpacemarkingSide_literals_[4] =
+{
+  "front",
+  "rear",
+  "left",
+  "right"
+};
+
+const parkingSpacemarkingSide::value parkingSpacemarkingSide::
+_xsd_parkingSpacemarkingSide_indexes_[4] =
+{
+  ::parkingSpacemarkingSide::front,
+  ::parkingSpacemarkingSide::left,
+  ::parkingSpacemarkingSide::rear,
+  ::parkingSpacemarkingSide::right
+};
+
+// dynamic
+//
+
+dynamic::
+dynamic (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_dynamic_convert ();
+}
+
+dynamic::
+dynamic (const ::xercesc::DOMAttr& a,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_dynamic_convert ();
+}
+
+dynamic::
+dynamic (const ::std::string& s,
+         const ::xercesc::DOMElement* e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_dynamic_convert ();
+}
+
+dynamic* dynamic::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class dynamic (*this, f, c);
+}
+
+dynamic::value dynamic::
+_xsd_dynamic_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_dynamic_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_dynamic_indexes_,
+                    _xsd_dynamic_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_dynamic_indexes_ + 2 || _xsd_dynamic_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const dynamic::
+_xsd_dynamic_literals_[2] =
+{
+  "yes",
+  "no"
+};
+
+const dynamic::value dynamic::
+_xsd_dynamic_indexes_[2] =
+{
+  ::dynamic::no,
+  ::dynamic::yes
+};
+
+// surfaceOrientation
+//
+
+surfaceOrientation::
+surfaceOrientation (const ::xercesc::DOMElement& e,
+                    ::xml_schema::flags f,
+                    ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_surfaceOrientation_convert ();
+}
+
+surfaceOrientation::
+surfaceOrientation (const ::xercesc::DOMAttr& a,
+                    ::xml_schema::flags f,
+                    ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_surfaceOrientation_convert ();
+}
+
+surfaceOrientation::
+surfaceOrientation (const ::std::string& s,
+                    const ::xercesc::DOMElement* e,
+                    ::xml_schema::flags f,
+                    ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_surfaceOrientation_convert ();
+}
+
+surfaceOrientation* surfaceOrientation::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class surfaceOrientation (*this, f, c);
+}
+
+surfaceOrientation::value surfaceOrientation::
+_xsd_surfaceOrientation_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_surfaceOrientation_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_surfaceOrientation_indexes_,
+                    _xsd_surfaceOrientation_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_surfaceOrientation_indexes_ + 2 || _xsd_surfaceOrientation_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const surfaceOrientation::
+_xsd_surfaceOrientation_literals_[2] =
+{
+  "same",
+  "opposite"
+};
+
+const surfaceOrientation::value surfaceOrientation::
+_xsd_surfaceOrientation_indexes_[2] =
+{
+  ::surfaceOrientation::opposite,
+  ::surfaceOrientation::same
+};
+
+// mode
+//
+
+mode::
+mode (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_mode_convert ();
+}
+
+mode::
+mode (const ::xercesc::DOMAttr& a,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_mode_convert ();
+}
+
+mode::
+mode (const ::std::string& s,
+      const ::xercesc::DOMElement* e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_mode_convert ();
+}
+
+mode* mode::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class mode (*this, f, c);
+}
+
+mode::value mode::
+_xsd_mode_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_mode_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_mode_indexes_,
+                    _xsd_mode_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_mode_indexes_ + 3 || _xsd_mode_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const mode::
+_xsd_mode_literals_[3] =
+{
+  "attached",
+  "attached0",
+  "genuine"
+};
+
+const mode::value mode::
+_xsd_mode_indexes_[3] =
+{
+  ::mode::attached,
+  ::mode::attached0,
+  ::mode::genuine
+};
+
+// purpose
+//
+
+purpose::
+purpose (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_purpose_convert ();
+}
+
+purpose::
+purpose (const ::xercesc::DOMAttr& a,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_purpose_convert ();
+}
+
+purpose::
+purpose (const ::std::string& s,
+         const ::xercesc::DOMElement* e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_purpose_convert ();
+}
+
+purpose* purpose::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class purpose (*this, f, c);
+}
+
+purpose::value purpose::
+_xsd_purpose_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_purpose_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_purpose_indexes_,
+                    _xsd_purpose_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_purpose_indexes_ + 2 || _xsd_purpose_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const purpose::
+_xsd_purpose_literals_[2] =
+{
+  "elevation",
+  "friction"
+};
+
+const purpose::value purpose::
+_xsd_purpose_indexes_[2] =
+{
+  ::purpose::elevation,
+  ::purpose::friction
+};
+
+// position
+//
+
+position::
+position (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_position_convert ();
+}
+
+position::
+position (const ::xercesc::DOMAttr& a,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_position_convert ();
+}
+
+position::
+position (const ::std::string& s,
+          const ::xercesc::DOMElement* e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_position_convert ();
+}
+
+position* position::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class position (*this, f, c);
+}
+
+position::value position::
+_xsd_position_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_position_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_position_indexes_,
+                    _xsd_position_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_position_indexes_ + 3 || _xsd_position_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const position::
+_xsd_position_literals_[3] =
+{
+  "dynamic",
+  "straight",
+  "turn"
+};
+
+const position::value position::
+_xsd_position_indexes_[3] =
+{
+  ::position::dynamic,
+  ::position::straight,
+  ::position::turn
+};
+
+// dir
+//
+
+dir::
+dir (const ::xercesc::DOMElement& e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_dir_convert ();
+}
+
+dir::
+dir (const ::xercesc::DOMAttr& a,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_dir_convert ();
+}
+
+dir::
+dir (const ::std::string& s,
+     const ::xercesc::DOMElement* e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_dir_convert ();
+}
+
+dir* dir::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class dir (*this, f, c);
+}
+
+dir::value dir::
+_xsd_dir_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_dir_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_dir_indexes_,
+                    _xsd_dir_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_dir_indexes_ + 2 || _xsd_dir_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const dir::
+_xsd_dir_literals_[2] =
+{
+  "+",
+  "-"
+};
+
+const dir::value dir::
+_xsd_dir_indexes_[2] =
+{
+  ::dir::cxx_,
+  ::dir::cxx_1
+};
+
+// junctionGroupType
+//
+
+junctionGroupType::
+junctionGroupType (const ::xercesc::DOMElement& e,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_junctionGroupType_convert ();
+}
+
+junctionGroupType::
+junctionGroupType (const ::xercesc::DOMAttr& a,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_junctionGroupType_convert ();
+}
+
+junctionGroupType::
+junctionGroupType (const ::std::string& s,
+                   const ::xercesc::DOMElement* e,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_junctionGroupType_convert ();
+}
+
+junctionGroupType* junctionGroupType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class junctionGroupType (*this, f, c);
+}
+
+junctionGroupType::value junctionGroupType::
+_xsd_junctionGroupType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_junctionGroupType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_junctionGroupType_indexes_,
+                    _xsd_junctionGroupType_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_junctionGroupType_indexes_ + 2 || _xsd_junctionGroupType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const junctionGroupType::
+_xsd_junctionGroupType_literals_[2] =
+{
+  "roundabout",
+  "unknown"
+};
+
+const junctionGroupType::value junctionGroupType::
+_xsd_junctionGroupType_indexes_[2] =
+{
+  ::junctionGroupType::roundabout,
+  ::junctionGroupType::unknown
+};
+
+// stationType
+//
+
+stationType::
+stationType (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_stationType_convert ();
+}
+
+stationType::
+stationType (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_stationType_convert ();
+}
+
+stationType::
+stationType (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_stationType_convert ();
+}
+
+stationType* stationType::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class stationType (*this, f, c);
+}
+
+stationType::value stationType::
+_xsd_stationType_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_stationType_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_stationType_indexes_,
+                    _xsd_stationType_indexes_ + 3,
+                    *this,
+                    c));
+
+  if (i == _xsd_stationType_indexes_ + 3 || _xsd_stationType_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const stationType::
+_xsd_stationType_literals_[3] =
+{
+  "small",
+  "medium",
+  "large"
+};
+
+const stationType::value stationType::
+_xsd_stationType_indexes_[3] =
+{
+  ::stationType::large,
+  ::stationType::medium,
+  ::stationType::small
+};
+
+// userData
+//
+
+userData::
+userData ()
+: ::xml_schema::type (),
+  code_ (this),
+  value_ (this)
+{
+}
+
+userData::
+userData (const userData& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  code_ (x.code_, f, this),
+  value_ (x.value_, f, this)
+{
+}
+
+userData::
+userData (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  code_ (this),
+  value_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void userData::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "code" && n.namespace_ ().empty ())
+    {
+      this->code_.set (code_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "value" && n.namespace_ ().empty ())
+    {
+      this->value_.set (value_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+userData* userData::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class userData (*this, f, c);
+}
+
+userData& userData::
+operator= (const userData& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->code_ = x.code_;
+    this->value_ = x.value_;
+  }
+
+  return *this;
+}
+
+userData::
+~userData ()
+{
+}
+
+// include
+//
+
+include::
+include ()
+: ::xml_schema::type (),
+  file_ (this)
+{
+}
+
+include::
+include (const include& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  file_ (x.file_, f, this)
+{
+}
+
+include::
+include (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  file_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void include::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "file" && n.namespace_ ().empty ())
+    {
+      this->file_.set (file_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+include* include::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class include (*this, f, c);
+}
+
+include& include::
+operator= (const include& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->file_ = x.file_;
+  }
+
+  return *this;
+}
+
+include::
+~include ()
+{
+}
+
+// laneValidity
+//
+
+laneValidity::
+laneValidity ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  fromLane_ (this),
+  toLane_ (this)
+{
+}
+
+laneValidity::
+laneValidity (const laneValidity& x,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  fromLane_ (x.fromLane_, f, this),
+  toLane_ (x.toLane_, f, this)
+{
+}
+
+laneValidity::
+laneValidity (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  fromLane_ (this),
+  toLane_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void laneValidity::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "fromLane" && n.namespace_ ().empty ())
+    {
+      this->fromLane_.set (fromLane_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "toLane" && n.namespace_ ().empty ())
+    {
+      this->toLane_.set (toLane_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+laneValidity* laneValidity::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneValidity (*this, f, c);
+}
+
+laneValidity& laneValidity::
+operator= (const laneValidity& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->fromLane_ = x.fromLane_;
+    this->toLane_ = x.toLane_;
+  }
+
+  return *this;
+}
+
+laneValidity::
+~laneValidity ()
+{
+}
+
+// parkingSpace
+//
+
+parkingSpace::
+parkingSpace ()
+: ::xml_schema::type (),
+  marking_ (this),
+  userData_ (this),
+  include_ (this),
+  parkingSpace_access_ (this),
+  restrictions_ (this)
+{
+}
+
+parkingSpace::
+parkingSpace (const parkingSpace& x,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  marking_ (x.marking_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  parkingSpace_access_ (x.parkingSpace_access_, f, this),
+  restrictions_ (x.restrictions_, f, this)
+{
+}
+
+parkingSpace::
+parkingSpace (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  marking_ (this),
+  userData_ (this),
+  include_ (this),
+  parkingSpace_access_ (this),
+  restrictions_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void parkingSpace::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // marking
+    //
+    if (n.name () == "marking" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< marking_type > r (
+        marking_traits::create (i, f, this));
+
+      this->marking_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "access" && n.namespace_ ().empty ())
+    {
+      this->parkingSpace_access_.set (access_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "restrictions" && n.namespace_ ().empty ())
+    {
+      this->restrictions_.set (restrictions_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+parkingSpace* parkingSpace::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class parkingSpace (*this, f, c);
+}
+
+parkingSpace& parkingSpace::
+operator= (const parkingSpace& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->marking_ = x.marking_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->parkingSpace_access_ = x.parkingSpace_access_;
+    this->restrictions_ = x.restrictions_;
+  }
+
+  return *this;
+}
+
+parkingSpace::
+~parkingSpace ()
+{
+}
+
+// lane
+//
+
+lane::
+lane ()
+: ::xml_schema::type (),
+  lane_link_ (this),
+  width_ (this),
+  border_ (this),
+  roadMark_ (this),
+  material_ (this),
+  visibility_ (this),
+  speed_ (this),
+  parkingSpace_access_ (this),
+  height_ (this),
+  rule_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  level_ (this)
+{
+}
+
+lane::
+lane (const lane& x,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_link_ (x.lane_link_, f, this),
+  width_ (x.width_, f, this),
+  border_ (x.border_, f, this),
+  roadMark_ (x.roadMark_, f, this),
+  material_ (x.material_, f, this),
+  visibility_ (x.visibility_, f, this),
+  speed_ (x.speed_, f, this),
+  parkingSpace_access_ (x.parkingSpace_access_, f, this),
+  height_ (x.height_, f, this),
+  rule_ (x.rule_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this),
+  level_ (x.level_, f, this)
+{
+}
+
+lane::
+lane (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_link_ (this),
+  width_ (this),
+  border_ (this),
+  roadMark_ (this),
+  material_ (this),
+  visibility_ (this),
+  speed_ (this),
+  parkingSpace_access_ (this),
+  height_ (this),
+  rule_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  level_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void lane::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // link
+    //
+    if (n.name () == "link" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< link_type > r (
+        link_traits::create (i, f, this));
+
+      if (!this->lane_link_)
+      {
+        this->lane_link_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // width
+    //
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< width_type > r (
+        width_traits::create (i, f, this));
+
+      this->width_.push_back (::std::move (r));
+      continue;
+    }
+
+    // border
+    //
+    if (n.name () == "border" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< border_type > r (
+        border_traits::create (i, f, this));
+
+      this->border_.push_back (::std::move (r));
+      continue;
+    }
+
+    // roadMark
+    //
+    if (n.name () == "roadMark" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< roadMark_type > r (
+        roadMark_traits::create (i, f, this));
+
+      this->roadMark_.push_back (::std::move (r));
+      continue;
+    }
+
+    // material
+    //
+    if (n.name () == "material" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< material_type > r (
+        material_traits::create (i, f, this));
+
+      this->material_.push_back (::std::move (r));
+      continue;
+    }
+
+    // visibility
+    //
+    if (n.name () == "visibility" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< visibility_type > r (
+        visibility_traits::create (i, f, this));
+
+      this->visibility_.push_back (::std::move (r));
+      continue;
+    }
+
+    // speed
+    //
+    if (n.name () == "speed" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< speed_type > r (
+        speed_traits::create (i, f, this));
+
+      this->speed_.push_back (::std::move (r));
+      continue;
+    }
+
+    // access
+    //
+    if (n.name () == "access" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< access_type > r (
+        access_traits::create (i, f, this));
+
+      this->parkingSpace_access_.push_back (::std::move (r));
+      continue;
+    }
+
+    // height
+    //
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< height_type > r (
+        height_traits::create (i, f, this));
+
+      this->height_.push_back (::std::move (r));
+      continue;
+    }
+
+    // rule
+    //
+    if (n.name () == "rule" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< rule_type > r (
+        rule_traits::create (i, f, this));
+
+      this->rule_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "level" && n.namespace_ ().empty ())
+    {
+      this->level_.set (level_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+lane* lane::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class lane (*this, f, c);
+}
+
+lane& lane::
+operator= (const lane& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_link_ = x.lane_link_;
+    this->width_ = x.width_;
+    this->border_ = x.border_;
+    this->roadMark_ = x.roadMark_;
+    this->material_ = x.material_;
+    this->visibility_ = x.visibility_;
+    this->speed_ = x.speed_;
+    this->parkingSpace_access_ = x.parkingSpace_access_;
+    this->height_ = x.height_;
+    this->rule_ = x.rule_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+    this->level_ = x.level_;
+  }
+
+  return *this;
+}
+
+lane::
+~lane ()
+{
+}
+
+// centerLane
+//
+
+centerLane::
+centerLane ()
+: ::xml_schema::type (),
+  lane_link_ (this),
+  roadMark_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  level_ (this)
+{
+}
+
+centerLane::
+centerLane (const centerLane& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_link_ (x.lane_link_, f, this),
+  roadMark_ (x.roadMark_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this),
+  level_ (x.level_, f, this)
+{
+}
+
+centerLane::
+centerLane (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_link_ (this),
+  roadMark_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  level_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void centerLane::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // link
+    //
+    if (n.name () == "link" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< link_type > r (
+        link_traits::create (i, f, this));
+
+      if (!this->lane_link_)
+      {
+        this->lane_link_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // roadMark
+    //
+    if (n.name () == "roadMark" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< roadMark_type > r (
+        roadMark_traits::create (i, f, this));
+
+      this->roadMark_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "level" && n.namespace_ ().empty ())
+    {
+      this->level_.set (level_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+centerLane* centerLane::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class centerLane (*this, f, c);
+}
+
+centerLane& centerLane::
+operator= (const centerLane& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_link_ = x.lane_link_;
+    this->roadMark_ = x.roadMark_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+    this->level_ = x.level_;
+  }
+
+  return *this;
+}
+
+centerLane::
+~centerLane ()
+{
+}
+
+// OpenDRIVE
+//
+
+OpenDRIVE::
+OpenDRIVE (const header_type& header)
+: ::xml_schema::type (),
+  header_ (header, this),
+  road_ (this),
+  controller_ (this),
+  junction_ (this),
+  junctionGroup_ (this),
+  station_ (this)
+{
+}
+
+OpenDRIVE::
+OpenDRIVE (::std::unique_ptr< header_type > header)
+: ::xml_schema::type (),
+  header_ (std::move (header), this),
+  road_ (this),
+  controller_ (this),
+  junction_ (this),
+  junctionGroup_ (this),
+  station_ (this)
+{
+}
+
+OpenDRIVE::
+OpenDRIVE (const OpenDRIVE& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  header_ (x.header_, f, this),
+  road_ (x.road_, f, this),
+  controller_ (x.controller_, f, this),
+  junction_ (x.junction_, f, this),
+  junctionGroup_ (x.junctionGroup_, f, this),
+  station_ (x.station_, f, this)
+{
+}
+
+OpenDRIVE::
+OpenDRIVE (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  header_ (this),
+  road_ (this),
+  controller_ (this),
+  junction_ (this),
+  junctionGroup_ (this),
+  station_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void OpenDRIVE::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // header
+    //
+    if (n.name () == "header" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< header_type > r (
+        header_traits::create (i, f, this));
+
+      if (!header_.present ())
+      {
+        this->header_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // road
+    //
+    if (n.name () == "road" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< road_type > r (
+        road_traits::create (i, f, this));
+
+      this->road_.push_back (::std::move (r));
+      continue;
+    }
+
+    // controller
+    //
+    if (n.name () == "controller" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< controller_type > r (
+        controller_traits::create (i, f, this));
+
+      this->controller_.push_back (::std::move (r));
+      continue;
+    }
+
+    // junction
+    //
+    if (n.name () == "junction" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< junction_type > r (
+        junction_traits::create (i, f, this));
+
+      this->junction_.push_back (::std::move (r));
+      continue;
+    }
+
+    // junctionGroup
+    //
+    if (n.name () == "junctionGroup" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< junctionGroup_type > r (
+        junctionGroup_traits::create (i, f, this));
+
+      this->junctionGroup_.push_back (::std::move (r));
+      continue;
+    }
+
+    // station
+    //
+    if (n.name () == "station" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< station_type > r (
+        station_traits::create (i, f, this));
+
+      this->station_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  if (!header_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "header",
+      "");
+  }
+}
+
+OpenDRIVE* OpenDRIVE::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class OpenDRIVE (*this, f, c);
+}
+
+OpenDRIVE& OpenDRIVE::
+operator= (const OpenDRIVE& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->header_ = x.header_;
+    this->road_ = x.road_;
+    this->controller_ = x.controller_;
+    this->junction_ = x.junction_;
+    this->junctionGroup_ = x.junctionGroup_;
+    this->station_ = x.station_;
+  }
+
+  return *this;
+}
+
+OpenDRIVE::
+~OpenDRIVE ()
+{
+}
+
+// max_member
+//
+
+max_member::
+max_member (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (e, f, c)
+{
+  _xsd_max_member_convert ();
+}
+
+max_member::
+max_member (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (a, f, c)
+{
+  _xsd_max_member_convert ();
+}
+
+max_member::
+max_member (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::string (s, e, f, c)
+{
+  _xsd_max_member_convert ();
+}
+
+max_member* max_member::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class max_member (*this, f, c);
+}
+
+max_member::value max_member::
+_xsd_max_member_convert () const
+{
+  ::xsd::cxx::tree::enum_comparator< char > c (_xsd_max_member_literals_);
+  const value* i (::std::lower_bound (
+                    _xsd_max_member_indexes_,
+                    _xsd_max_member_indexes_ + 2,
+                    *this,
+                    c));
+
+  if (i == _xsd_max_member_indexes_ + 2 || _xsd_max_member_literals_[*i] != *this)
+  {
+    throw ::xsd::cxx::tree::unexpected_enumerator < char > (*this);
+  }
+
+  return *i;
+}
+
+const char* const max_member::
+_xsd_max_member_literals_[2] =
+{
+  "no limit",
+  "undefined"
+};
+
+const max_member::value max_member::
+_xsd_max_member_indexes_[2] =
+{
+  ::max_member::no_limit,
+  ::max_member::undefined
+};
+
+// max_member1
+//
+
+max_member1::
+max_member1 (const ::xml_schema::integer& _xsd_integer_base)
+: ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type > (_xsd_integer_base)
+{
+}
+
+max_member1::
+max_member1 (const max_member1& x,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type > (x, f, c)
+{
+}
+
+max_member1::
+max_member1 (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type > (e, f, c)
+{
+}
+
+max_member1::
+max_member1 (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type > (a, f, c)
+{
+}
+
+max_member1::
+max_member1 (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type > (s, e, f, c)
+{
+}
+
+max_member1* max_member1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class max_member1 (*this, f, c);
+}
+
+max_member1::
+~max_member1 ()
+{
+}
+
+// marking
+//
+
+marking::
+marking ()
+: ::xml_schema::type (),
+  side_ (this),
+  type_ (this),
+  width_ (this),
+  color_ (this)
+{
+}
+
+marking::
+marking (const marking& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  side_ (x.side_, f, this),
+  type_ (x.type_, f, this),
+  width_ (x.width_, f, this),
+  color_ (x.color_, f, this)
+{
+}
+
+marking::
+marking (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  side_ (this),
+  type_ (this),
+  width_ (this),
+  color_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void marking::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "side" && n.namespace_ ().empty ())
+    {
+      this->side_.set (side_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "color" && n.namespace_ ().empty ())
+    {
+      this->color_.set (color_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+marking* marking::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class marking (*this, f, c);
+}
+
+marking& marking::
+operator= (const marking& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->side_ = x.side_;
+    this->type_ = x.type_;
+    this->width_ = x.width_;
+    this->color_ = x.color_;
+  }
+
+  return *this;
+}
+
+marking::
+~marking ()
+{
+}
+
+// lane_link
+//
+
+lane_link::
+lane_link ()
+: ::xml_schema::type (),
+  predecessor_ (this),
+  successor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+lane_link::
+lane_link (const lane_link& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  predecessor_ (x.predecessor_, f, this),
+  successor_ (x.successor_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+lane_link::
+lane_link (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  predecessor_ (this),
+  successor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void lane_link::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // predecessor
+    //
+    if (n.name () == "predecessor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< predecessor_type > r (
+        predecessor_traits::create (i, f, this));
+
+      if (!this->predecessor_)
+      {
+        this->predecessor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // successor
+    //
+    if (n.name () == "successor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< successor_type > r (
+        successor_traits::create (i, f, this));
+
+      if (!this->successor_)
+      {
+        this->successor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+lane_link* lane_link::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class lane_link (*this, f, c);
+}
+
+lane_link& lane_link::
+operator= (const lane_link& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->predecessor_ = x.predecessor_;
+    this->successor_ = x.successor_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+lane_link::
+~lane_link ()
+{
+}
+
+// width
+//
+
+width::
+width ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+width::
+width (const width& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+width::
+width (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void width::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+width* width::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class width (*this, f, c);
+}
+
+width& width::
+operator= (const width& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+width::
+~width ()
+{
+}
+
+// border
+//
+
+border::
+border ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+border::
+border (const border& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+border::
+border (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void border::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+border* border::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class border (*this, f, c);
+}
+
+border& border::
+operator= (const border& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+border::
+~border ()
+{
+}
+
+// roadMark
+//
+
+roadMark::
+roadMark ()
+: ::xml_schema::type (),
+  type_ (this),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  type1_ (this),
+  weight_ (this),
+  color_ (this),
+  material_ (this),
+  width_ (this),
+  laneChange_ (this),
+  height_ (this)
+{
+}
+
+roadMark::
+roadMark (const roadMark& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  type_ (x.type_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  type1_ (x.type1_, f, this),
+  weight_ (x.weight_, f, this),
+  color_ (x.color_, f, this),
+  material_ (x.material_, f, this),
+  width_ (x.width_, f, this),
+  laneChange_ (x.laneChange_, f, this),
+  height_ (x.height_, f, this)
+{
+}
+
+roadMark::
+roadMark (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  type_ (this),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  type1_ (this),
+  weight_ (this),
+  color_ (this),
+  material_ (this),
+  width_ (this),
+  laneChange_ (this),
+  height_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void roadMark::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // type
+    //
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< type_type > r (
+        type_traits::create (i, f, this));
+
+      if (!this->type_)
+      {
+        this->type_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type1_.set (type1_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "weight" && n.namespace_ ().empty ())
+    {
+      this->weight_.set (weight_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "color" && n.namespace_ ().empty ())
+    {
+      this->color_.set (color_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "material" && n.namespace_ ().empty ())
+    {
+      this->material_.set (material_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "laneChange" && n.namespace_ ().empty ())
+    {
+      this->laneChange_.set (laneChange_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+roadMark* roadMark::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class roadMark (*this, f, c);
+}
+
+roadMark& roadMark::
+operator= (const roadMark& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->type_ = x.type_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->type1_ = x.type1_;
+    this->weight_ = x.weight_;
+    this->color_ = x.color_;
+    this->material_ = x.material_;
+    this->width_ = x.width_;
+    this->laneChange_ = x.laneChange_;
+    this->height_ = x.height_;
+  }
+
+  return *this;
+}
+
+roadMark::
+~roadMark ()
+{
+}
+
+// material
+//
+
+material::
+material ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  surface_ (this),
+  friction_ (this),
+  roughness_ (this)
+{
+}
+
+material::
+material (const material& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  surface_ (x.surface_, f, this),
+  friction_ (x.friction_, f, this),
+  roughness_ (x.roughness_, f, this)
+{
+}
+
+material::
+material (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  surface_ (this),
+  friction_ (this),
+  roughness_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void material::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "surface" && n.namespace_ ().empty ())
+    {
+      this->surface_.set (surface_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "friction" && n.namespace_ ().empty ())
+    {
+      this->friction_.set (friction_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "roughness" && n.namespace_ ().empty ())
+    {
+      this->roughness_.set (roughness_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+material* material::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class material (*this, f, c);
+}
+
+material& material::
+operator= (const material& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->surface_ = x.surface_;
+    this->friction_ = x.friction_;
+    this->roughness_ = x.roughness_;
+  }
+
+  return *this;
+}
+
+material::
+~material ()
+{
+}
+
+// visibility
+//
+
+visibility::
+visibility ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  forward_ (this),
+  back_ (this),
+  left_ (this),
+  right_ (this)
+{
+}
+
+visibility::
+visibility (const visibility& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  forward_ (x.forward_, f, this),
+  back_ (x.back_, f, this),
+  left_ (x.left_, f, this),
+  right_ (x.right_, f, this)
+{
+}
+
+visibility::
+visibility (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  forward_ (this),
+  back_ (this),
+  left_ (this),
+  right_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void visibility::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "forward" && n.namespace_ ().empty ())
+    {
+      this->forward_.set (forward_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "back" && n.namespace_ ().empty ())
+    {
+      this->back_.set (back_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "left" && n.namespace_ ().empty ())
+    {
+      this->left_.set (left_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "right" && n.namespace_ ().empty ())
+    {
+      this->right_.set (right_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+visibility* visibility::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class visibility (*this, f, c);
+}
+
+visibility& visibility::
+operator= (const visibility& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->forward_ = x.forward_;
+    this->back_ = x.back_;
+    this->left_ = x.left_;
+    this->right_ = x.right_;
+  }
+
+  return *this;
+}
+
+visibility::
+~visibility ()
+{
+}
+
+// speed
+//
+
+speed::
+speed ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  max_ (this),
+  unit_ (this)
+{
+}
+
+speed::
+speed (const speed& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  max_ (x.max_, f, this),
+  unit_ (x.unit_, f, this)
+{
+}
+
+speed::
+speed (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  max_ (this),
+  unit_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void speed::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "max" && n.namespace_ ().empty ())
+    {
+      this->max_.set (max_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "unit" && n.namespace_ ().empty ())
+    {
+      this->unit_.set (unit_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+speed* speed::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class speed (*this, f, c);
+}
+
+speed& speed::
+operator= (const speed& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->max_ = x.max_;
+    this->unit_ = x.unit_;
+  }
+
+  return *this;
+}
+
+speed::
+~speed ()
+{
+}
+
+// access1
+//
+
+access1::
+access1 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  restriction_ (this)
+{
+}
+
+access1::
+access1 (const access1& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  restriction_ (x.restriction_, f, this)
+{
+}
+
+access1::
+access1 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  restriction_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void access1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "restriction" && n.namespace_ ().empty ())
+    {
+      this->restriction_.set (restriction_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+access1* access1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class access1 (*this, f, c);
+}
+
+access1& access1::
+operator= (const access1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->restriction_ = x.restriction_;
+  }
+
+  return *this;
+}
+
+access1::
+~access1 ()
+{
+}
+
+// height
+//
+
+height::
+height ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  inner_ (this),
+  outer_ (this)
+{
+}
+
+height::
+height (const height& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  inner_ (x.inner_, f, this),
+  outer_ (x.outer_, f, this)
+{
+}
+
+height::
+height (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  inner_ (this),
+  outer_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void height::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "inner" && n.namespace_ ().empty ())
+    {
+      this->inner_.set (inner_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "outer" && n.namespace_ ().empty ())
+    {
+      this->outer_.set (outer_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+height* height::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class height (*this, f, c);
+}
+
+height& height::
+operator= (const height& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->inner_ = x.inner_;
+    this->outer_ = x.outer_;
+  }
+
+  return *this;
+}
+
+height::
+~height ()
+{
+}
+
+// rule1
+//
+
+rule1::
+rule1 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  value_ (this)
+{
+}
+
+rule1::
+rule1 (const rule1& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  value_ (x.value_, f, this)
+{
+}
+
+rule1::
+rule1 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  value_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void rule1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "value" && n.namespace_ ().empty ())
+    {
+      this->value_.set (value_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+rule1* rule1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class rule1 (*this, f, c);
+}
+
+rule1& rule1::
+operator= (const rule1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->value_ = x.value_;
+  }
+
+  return *this;
+}
+
+rule1::
+~rule1 ()
+{
+}
+
+// link1
+//
+
+link1::
+link1 ()
+: ::xml_schema::type (),
+  predecessor_ (this),
+  successor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+link1::
+link1 (const link1& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  predecessor_ (x.predecessor_, f, this),
+  successor_ (x.successor_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+link1::
+link1 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  predecessor_ (this),
+  successor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void link1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // predecessor
+    //
+    if (n.name () == "predecessor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< predecessor_type > r (
+        predecessor_traits::create (i, f, this));
+
+      if (!this->predecessor_)
+      {
+        this->predecessor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // successor
+    //
+    if (n.name () == "successor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< successor_type > r (
+        successor_traits::create (i, f, this));
+
+      if (!this->successor_)
+      {
+        this->successor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+link1* link1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class link1 (*this, f, c);
+}
+
+link1& link1::
+operator= (const link1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->predecessor_ = x.predecessor_;
+    this->successor_ = x.successor_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+link1::
+~link1 ()
+{
+}
+
+// roadMark1
+//
+
+roadMark1::
+roadMark1 ()
+: ::xml_schema::type (),
+  type_ (this),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  type1_ (this),
+  weight_ (this),
+  color_ (this),
+  material_ (this),
+  width_ (this),
+  laneChange_ (this),
+  height_ (this)
+{
+}
+
+roadMark1::
+roadMark1 (const roadMark1& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  type_ (x.type_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  type1_ (x.type1_, f, this),
+  weight_ (x.weight_, f, this),
+  color_ (x.color_, f, this),
+  material_ (x.material_, f, this),
+  width_ (x.width_, f, this),
+  laneChange_ (x.laneChange_, f, this),
+  height_ (x.height_, f, this)
+{
+}
+
+roadMark1::
+roadMark1 (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  type_ (this),
+  userData_ (this),
+  include_ (this),
+  sOffset_ (this),
+  type1_ (this),
+  weight_ (this),
+  color_ (this),
+  material_ (this),
+  width_ (this),
+  laneChange_ (this),
+  height_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void roadMark1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // type
+    //
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< type_type > r (
+        type_traits::create (i, f, this));
+
+      if (!this->type_)
+      {
+        this->type_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type1_.set (type1_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "weight" && n.namespace_ ().empty ())
+    {
+      this->weight_.set (weight_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "color" && n.namespace_ ().empty ())
+    {
+      this->color_.set (color_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "material" && n.namespace_ ().empty ())
+    {
+      this->material_.set (material_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "laneChange" && n.namespace_ ().empty ())
+    {
+      this->laneChange_.set (laneChange_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+roadMark1* roadMark1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class roadMark1 (*this, f, c);
+}
+
+roadMark1& roadMark1::
+operator= (const roadMark1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->type_ = x.type_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->sOffset_ = x.sOffset_;
+    this->type1_ = x.type1_;
+    this->weight_ = x.weight_;
+    this->color_ = x.color_;
+    this->material_ = x.material_;
+    this->width_ = x.width_;
+    this->laneChange_ = x.laneChange_;
+    this->height_ = x.height_;
+  }
+
+  return *this;
+}
+
+roadMark1::
+~roadMark1 ()
+{
+}
+
+// header
+//
+
+header::
+header ()
+: ::xml_schema::type (),
+  geoReference_ (this),
+  userData_ (this),
+  include_ (this),
+  revMajor_ (this),
+  revMinor_ (this),
+  name_ (this),
+  version_ (this),
+  date_ (this),
+  north_ (this),
+  south_ (this),
+  east_ (this),
+  west_ (this),
+  vendor_ (this)
+{
+}
+
+header::
+header (const header& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  geoReference_ (x.geoReference_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  revMajor_ (x.revMajor_, f, this),
+  revMinor_ (x.revMinor_, f, this),
+  name_ (x.name_, f, this),
+  version_ (x.version_, f, this),
+  date_ (x.date_, f, this),
+  north_ (x.north_, f, this),
+  south_ (x.south_, f, this),
+  east_ (x.east_, f, this),
+  west_ (x.west_, f, this),
+  vendor_ (x.vendor_, f, this)
+{
+}
+
+header::
+header (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  geoReference_ (this),
+  userData_ (this),
+  include_ (this),
+  revMajor_ (this),
+  revMinor_ (this),
+  name_ (this),
+  version_ (this),
+  date_ (this),
+  north_ (this),
+  south_ (this),
+  east_ (this),
+  west_ (this),
+  vendor_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void header::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // geoReference
+    //
+    if (n.name () == "geoReference" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< geoReference_type > r (
+        geoReference_traits::create (i, f, this));
+
+      if (!this->geoReference_)
+      {
+        this->geoReference_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "revMajor" && n.namespace_ ().empty ())
+    {
+      this->revMajor_.set (revMajor_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "revMinor" && n.namespace_ ().empty ())
+    {
+      this->revMinor_.set (revMinor_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "version" && n.namespace_ ().empty ())
+    {
+      this->version_.set (version_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "date" && n.namespace_ ().empty ())
+    {
+      this->date_.set (date_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "north" && n.namespace_ ().empty ())
+    {
+      this->north_.set (north_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "south" && n.namespace_ ().empty ())
+    {
+      this->south_.set (south_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "east" && n.namespace_ ().empty ())
+    {
+      this->east_.set (east_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "west" && n.namespace_ ().empty ())
+    {
+      this->west_.set (west_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "vendor" && n.namespace_ ().empty ())
+    {
+      this->vendor_.set (vendor_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+header* header::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class header (*this, f, c);
+}
+
+header& header::
+operator= (const header& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->geoReference_ = x.geoReference_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->revMajor_ = x.revMajor_;
+    this->revMinor_ = x.revMinor_;
+    this->name_ = x.name_;
+    this->version_ = x.version_;
+    this->date_ = x.date_;
+    this->north_ = x.north_;
+    this->south_ = x.south_;
+    this->east_ = x.east_;
+    this->west_ = x.west_;
+    this->vendor_ = x.vendor_;
+  }
+
+  return *this;
+}
+
+header::
+~header ()
+{
+}
+
+// road
+//
+
+road::
+road (const planView_type& planView,
+      const lanes_type& lanes)
+: ::xml_schema::type (),
+  lane_link_ (this),
+  type_ (this),
+  planView_ (planView, this),
+  elevationProfile_ (this),
+  lateralProfile_ (this),
+  lanes_ (lanes, this),
+  objects_ (this),
+  signals_ (this),
+  surface_ (this),
+  railroad_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  length_ (this),
+  id_ (this),
+  junction_ (this)
+{
+}
+
+road::
+road (::std::unique_ptr< planView_type > planView,
+      ::std::unique_ptr< lanes_type > lanes)
+: ::xml_schema::type (),
+  lane_link_ (this),
+  type_ (this),
+  planView_ (std::move (planView), this),
+  elevationProfile_ (this),
+  lateralProfile_ (this),
+  lanes_ (std::move (lanes), this),
+  objects_ (this),
+  signals_ (this),
+  surface_ (this),
+  railroad_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  length_ (this),
+  id_ (this),
+  junction_ (this)
+{
+}
+
+road::
+road (const road& x,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_link_ (x.lane_link_, f, this),
+  type_ (x.type_, f, this),
+  planView_ (x.planView_, f, this),
+  elevationProfile_ (x.elevationProfile_, f, this),
+  lateralProfile_ (x.lateralProfile_, f, this),
+  lanes_ (x.lanes_, f, this),
+  objects_ (x.objects_, f, this),
+  signals_ (x.signals_, f, this),
+  surface_ (x.surface_, f, this),
+  railroad_ (x.railroad_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  name_ (x.name_, f, this),
+  length_ (x.length_, f, this),
+  id_ (x.id_, f, this),
+  junction_ (x.junction_, f, this)
+{
+}
+
+road::
+road (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_link_ (this),
+  type_ (this),
+  planView_ (this),
+  elevationProfile_ (this),
+  lateralProfile_ (this),
+  lanes_ (this),
+  objects_ (this),
+  signals_ (this),
+  surface_ (this),
+  railroad_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  length_ (this),
+  id_ (this),
+  junction_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void road::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // link
+    //
+    if (n.name () == "link" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< link_type > r (
+        link_traits::create (i, f, this));
+
+      if (!this->lane_link_)
+      {
+        this->lane_link_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // type
+    //
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< type_type > r (
+        type_traits::create (i, f, this));
+
+      this->type_.push_back (::std::move (r));
+      continue;
+    }
+
+    // planView
+    //
+    if (n.name () == "planView" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< planView_type > r (
+        planView_traits::create (i, f, this));
+
+      if (!planView_.present ())
+      {
+        this->planView_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // elevationProfile
+    //
+    if (n.name () == "elevationProfile" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< elevationProfile_type > r (
+        elevationProfile_traits::create (i, f, this));
+
+      if (!this->elevationProfile_)
+      {
+        this->elevationProfile_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // lateralProfile
+    //
+    if (n.name () == "lateralProfile" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< lateralProfile_type > r (
+        lateralProfile_traits::create (i, f, this));
+
+      if (!this->lateralProfile_)
+      {
+        this->lateralProfile_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // lanes
+    //
+    if (n.name () == "lanes" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< lanes_type > r (
+        lanes_traits::create (i, f, this));
+
+      if (!lanes_.present ())
+      {
+        this->lanes_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // objects
+    //
+    if (n.name () == "objects" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< objects_type > r (
+        objects_traits::create (i, f, this));
+
+      if (!this->objects_)
+      {
+        this->objects_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // signals
+    //
+    if (n.name () == "signals" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< signals_type > r (
+        signals_traits::create (i, f, this));
+
+      if (!this->signals_)
+      {
+        this->signals_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // surface
+    //
+    if (n.name () == "surface" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< surface_type > r (
+        surface_traits::create (i, f, this));
+
+      if (!this->surface_)
+      {
+        this->surface_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // railroad
+    //
+    if (n.name () == "railroad" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< railroad_type > r (
+        railroad_traits::create (i, f, this));
+
+      if (!this->railroad_)
+      {
+        this->railroad_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  if (!planView_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "planView",
+      "");
+  }
+
+  if (!lanes_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "lanes",
+      "");
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "junction" && n.namespace_ ().empty ())
+    {
+      this->junction_.set (junction_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+road* road::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class road (*this, f, c);
+}
+
+road& road::
+operator= (const road& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_link_ = x.lane_link_;
+    this->type_ = x.type_;
+    this->planView_ = x.planView_;
+    this->elevationProfile_ = x.elevationProfile_;
+    this->lateralProfile_ = x.lateralProfile_;
+    this->lanes_ = x.lanes_;
+    this->objects_ = x.objects_;
+    this->signals_ = x.signals_;
+    this->surface_ = x.surface_;
+    this->railroad_ = x.railroad_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->name_ = x.name_;
+    this->length_ = x.length_;
+    this->id_ = x.id_;
+    this->junction_ = x.junction_;
+  }
+
+  return *this;
+}
+
+road::
+~road ()
+{
+}
+
+// controller
+//
+
+controller::
+controller ()
+: ::xml_schema::type (),
+  control_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  name_ (this),
+  sequence_ (this)
+{
+}
+
+controller::
+controller (const controller& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  control_ (x.control_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  name_ (x.name_, f, this),
+  sequence_ (x.sequence_, f, this)
+{
+}
+
+controller::
+controller (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  control_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  name_ (this),
+  sequence_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void controller::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // control
+    //
+    if (n.name () == "control" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< control_type > r (
+        control_traits::create (i, f, this));
+
+      this->control_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sequence" && n.namespace_ ().empty ())
+    {
+      this->sequence_.set (sequence_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+controller* controller::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class controller (*this, f, c);
+}
+
+controller& controller::
+operator= (const controller& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->control_ = x.control_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->name_ = x.name_;
+    this->sequence_ = x.sequence_;
+  }
+
+  return *this;
+}
+
+controller::
+~controller ()
+{
+}
+
+// junction
+//
+
+junction::
+junction ()
+: ::xml_schema::type (),
+  connection_ (this),
+  priority_ (this),
+  controller_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this)
+{
+}
+
+junction::
+junction (const junction& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  connection_ (x.connection_, f, this),
+  priority_ (x.priority_, f, this),
+  controller_ (x.controller_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this)
+{
+}
+
+junction::
+junction (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  connection_ (this),
+  priority_ (this),
+  controller_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void junction::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // connection
+    //
+    if (n.name () == "connection" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< connection_type > r (
+        connection_traits::create (i, f, this));
+
+      this->connection_.push_back (::std::move (r));
+      continue;
+    }
+
+    // priority
+    //
+    if (n.name () == "priority" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< priority_type > r (
+        priority_traits::create (i, f, this));
+
+      this->priority_.push_back (::std::move (r));
+      continue;
+    }
+
+    // controller
+    //
+    if (n.name () == "controller" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< controller_type > r (
+        controller_traits::create (i, f, this));
+
+      this->controller_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+junction* junction::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class junction (*this, f, c);
+}
+
+junction& junction::
+operator= (const junction& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->connection_ = x.connection_;
+    this->priority_ = x.priority_;
+    this->controller_ = x.controller_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+  }
+
+  return *this;
+}
+
+junction::
+~junction ()
+{
+}
+
+// junctionGroup
+//
+
+junctionGroup::
+junctionGroup ()
+: ::xml_schema::type (),
+  junctionReference_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+}
+
+junctionGroup::
+junctionGroup (const junctionGroup& x,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  junctionReference_ (x.junctionReference_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+junctionGroup::
+junctionGroup (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f,
+               ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  junctionReference_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void junctionGroup::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // junctionReference
+    //
+    if (n.name () == "junctionReference" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< junctionReference_type > r (
+        junctionReference_traits::create (i, f, this));
+
+      this->junctionReference_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+junctionGroup* junctionGroup::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class junctionGroup (*this, f, c);
+}
+
+junctionGroup& junctionGroup::
+operator= (const junctionGroup& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->junctionReference_ = x.junctionReference_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+junctionGroup::
+~junctionGroup ()
+{
+}
+
+// station
+//
+
+station::
+station ()
+: ::xml_schema::type (),
+  platform_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+}
+
+station::
+station (const station& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  platform_ (x.platform_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+station::
+station (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  platform_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void station::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // platform
+    //
+    if (n.name () == "platform" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< platform_type > r (
+        platform_traits::create (i, f, this));
+
+      this->platform_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+station* station::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class station (*this, f, c);
+}
+
+station& station::
+operator= (const station& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->platform_ = x.platform_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+station::
+~station ()
+{
+}
+
+// predecessor
+//
+
+predecessor::
+predecessor ()
+: ::xml_schema::type (),
+  id_ (this)
+{
+}
+
+predecessor::
+predecessor (const predecessor& x,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  id_ (x.id_, f, this)
+{
+}
+
+predecessor::
+predecessor (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  id_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void predecessor::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+predecessor* predecessor::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class predecessor (*this, f, c);
+}
+
+predecessor& predecessor::
+operator= (const predecessor& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->id_ = x.id_;
+  }
+
+  return *this;
+}
+
+predecessor::
+~predecessor ()
+{
+}
+
+// successor
+//
+
+successor::
+successor ()
+: ::xml_schema::type (),
+  id_ (this)
+{
+}
+
+successor::
+successor (const successor& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  id_ (x.id_, f, this)
+{
+}
+
+successor::
+successor (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  id_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void successor::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+successor* successor::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class successor (*this, f, c);
+}
+
+successor& successor::
+operator= (const successor& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->id_ = x.id_;
+  }
+
+  return *this;
+}
+
+successor::
+~successor ()
+{
+}
+
+// type
+//
+
+type::
+type ()
+: ::xml_schema::type (),
+  line_ (this),
+  name_ (this),
+  width_ (this)
+{
+}
+
+type::
+type (const type& x,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  line_ (x.line_, f, this),
+  name_ (x.name_, f, this),
+  width_ (x.width_, f, this)
+{
+}
+
+type::
+type (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  line_ (this),
+  name_ (this),
+  width_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void type::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // line
+    //
+    if (n.name () == "line" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< line_type > r (
+        line_traits::create (i, f, this));
+
+      this->line_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+type* type::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class type (*this, f, c);
+}
+
+type& type::
+operator= (const type& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->line_ = x.line_;
+    this->name_ = x.name_;
+    this->width_ = x.width_;
+  }
+
+  return *this;
+}
+
+type::
+~type ()
+{
+}
+
+// type1
+//
+
+type1::
+type1 ()
+: ::xml_schema::type (),
+  line_ (this),
+  name_ (this),
+  width_ (this)
+{
+}
+
+type1::
+type1 (const type1& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  line_ (x.line_, f, this),
+  name_ (x.name_, f, this),
+  width_ (x.width_, f, this)
+{
+}
+
+type1::
+type1 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  line_ (this),
+  name_ (this),
+  width_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void type1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // line
+    //
+    if (n.name () == "line" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< line_type > r (
+        line_traits::create (i, f, this));
+
+      this->line_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+type1* type1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class type1 (*this, f, c);
+}
+
+type1& type1::
+operator= (const type1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->line_ = x.line_;
+    this->name_ = x.name_;
+    this->width_ = x.width_;
+  }
+
+  return *this;
+}
+
+type1::
+~type1 ()
+{
+}
+
+// link2
+//
+
+link2::
+link2 ()
+: ::xml_schema::type (),
+  predecessor_ (this),
+  successor_ (this),
+  neighbor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+link2::
+link2 (const link2& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  predecessor_ (x.predecessor_, f, this),
+  successor_ (x.successor_, f, this),
+  neighbor_ (x.neighbor_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+link2::
+link2 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  predecessor_ (this),
+  successor_ (this),
+  neighbor_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void link2::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // predecessor
+    //
+    if (n.name () == "predecessor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< predecessor_type > r (
+        predecessor_traits::create (i, f, this));
+
+      if (!this->predecessor_)
+      {
+        this->predecessor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // successor
+    //
+    if (n.name () == "successor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< successor_type > r (
+        successor_traits::create (i, f, this));
+
+      if (!this->successor_)
+      {
+        this->successor_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // neighbor
+    //
+    if (n.name () == "neighbor" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< neighbor_type > r (
+        neighbor_traits::create (i, f, this));
+
+      this->neighbor_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+link2* link2::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class link2 (*this, f, c);
+}
+
+link2& link2::
+operator= (const link2& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->predecessor_ = x.predecessor_;
+    this->successor_ = x.successor_;
+    this->neighbor_ = x.neighbor_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+link2::
+~link2 ()
+{
+}
+
+// type2
+//
+
+type2::
+type2 ()
+: ::xml_schema::type (),
+  speed_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  type_ (this)
+{
+}
+
+type2::
+type2 (const type2& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  speed_ (x.speed_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+type2::
+type2 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  speed_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void type2::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // speed
+    //
+    if (n.name () == "speed" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< speed_type > r (
+        speed_traits::create (i, f, this));
+
+      if (!this->speed_)
+      {
+        this->speed_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+type2* type2::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class type2 (*this, f, c);
+}
+
+type2& type2::
+operator= (const type2& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->speed_ = x.speed_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+type2::
+~type2 ()
+{
+}
+
+// planView
+//
+
+planView::
+planView ()
+: ::xml_schema::type (),
+  geometry_ (this)
+{
+}
+
+planView::
+planView (const planView& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  geometry_ (x.geometry_, f, this)
+{
+}
+
+planView::
+planView (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  geometry_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void planView::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // geometry
+    //
+    if (n.name () == "geometry" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< geometry_type > r (
+        geometry_traits::create (i, f, this));
+
+      this->geometry_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+planView* planView::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class planView (*this, f, c);
+}
+
+planView& planView::
+operator= (const planView& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->geometry_ = x.geometry_;
+  }
+
+  return *this;
+}
+
+planView::
+~planView ()
+{
+}
+
+// elevationProfile
+//
+
+elevationProfile::
+elevationProfile ()
+: ::xml_schema::type (),
+  elevation_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+elevationProfile::
+elevationProfile (const elevationProfile& x,
+                  ::xml_schema::flags f,
+                  ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  elevation_ (x.elevation_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+elevationProfile::
+elevationProfile (const ::xercesc::DOMElement& e,
+                  ::xml_schema::flags f,
+                  ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  elevation_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void elevationProfile::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // elevation
+    //
+    if (n.name () == "elevation" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< elevation_type > r (
+        elevation_traits::create (i, f, this));
+
+      this->elevation_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+elevationProfile* elevationProfile::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class elevationProfile (*this, f, c);
+}
+
+elevationProfile& elevationProfile::
+operator= (const elevationProfile& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->elevation_ = x.elevation_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+elevationProfile::
+~elevationProfile ()
+{
+}
+
+// lateralProfile
+//
+
+lateralProfile::
+lateralProfile ()
+: ::xml_schema::type (),
+  superelevation_ (this),
+  crossfall_ (this),
+  shape_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+lateralProfile::
+lateralProfile (const lateralProfile& x,
+                ::xml_schema::flags f,
+                ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  superelevation_ (x.superelevation_, f, this),
+  crossfall_ (x.crossfall_, f, this),
+  shape_ (x.shape_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+lateralProfile::
+lateralProfile (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f,
+                ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  superelevation_ (this),
+  crossfall_ (this),
+  shape_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void lateralProfile::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // superelevation
+    //
+    if (n.name () == "superelevation" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< superelevation_type > r (
+        superelevation_traits::create (i, f, this));
+
+      this->superelevation_.push_back (::std::move (r));
+      continue;
+    }
+
+    // crossfall
+    //
+    if (n.name () == "crossfall" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< crossfall_type > r (
+        crossfall_traits::create (i, f, this));
+
+      this->crossfall_.push_back (::std::move (r));
+      continue;
+    }
+
+    // shape
+    //
+    if (n.name () == "shape" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< shape_type > r (
+        shape_traits::create (i, f, this));
+
+      this->shape_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+lateralProfile* lateralProfile::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class lateralProfile (*this, f, c);
+}
+
+lateralProfile& lateralProfile::
+operator= (const lateralProfile& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->superelevation_ = x.superelevation_;
+    this->crossfall_ = x.crossfall_;
+    this->shape_ = x.shape_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+lateralProfile::
+~lateralProfile ()
+{
+}
+
+// lanes
+//
+
+lanes::
+lanes ()
+: ::xml_schema::type (),
+  laneOffset_ (this),
+  laneSection_ (this)
+{
+}
+
+lanes::
+lanes (const lanes& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  laneOffset_ (x.laneOffset_, f, this),
+  laneSection_ (x.laneSection_, f, this)
+{
+}
+
+lanes::
+lanes (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  laneOffset_ (this),
+  laneSection_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void lanes::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // laneOffset
+    //
+    if (n.name () == "laneOffset" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< laneOffset_type > r (
+        laneOffset_traits::create (i, f, this));
+
+      this->laneOffset_.push_back (::std::move (r));
+      continue;
+    }
+
+    // laneSection
+    //
+    if (n.name () == "laneSection" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< laneSection_type > r (
+        laneSection_traits::create (i, f, this));
+
+      this->laneSection_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+lanes* lanes::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class lanes (*this, f, c);
+}
+
+lanes& lanes::
+operator= (const lanes& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->laneOffset_ = x.laneOffset_;
+    this->laneSection_ = x.laneSection_;
+  }
+
+  return *this;
+}
+
+lanes::
+~lanes ()
+{
+}
+
+// objects
+//
+
+objects::
+objects ()
+: ::xml_schema::type (),
+  object_ (this),
+  objectReference_ (this),
+  tunnel_ (this),
+  bridge_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+objects::
+objects (const objects& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  object_ (x.object_, f, this),
+  objectReference_ (x.objectReference_, f, this),
+  tunnel_ (x.tunnel_, f, this),
+  bridge_ (x.bridge_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+objects::
+objects (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  object_ (this),
+  objectReference_ (this),
+  tunnel_ (this),
+  bridge_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void objects::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // object
+    //
+    if (n.name () == "object" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< object_type > r (
+        object_traits::create (i, f, this));
+
+      this->object_.push_back (::std::move (r));
+      continue;
+    }
+
+    // objectReference
+    //
+    if (n.name () == "objectReference" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< objectReference_type > r (
+        objectReference_traits::create (i, f, this));
+
+      this->objectReference_.push_back (::std::move (r));
+      continue;
+    }
+
+    // tunnel
+    //
+    if (n.name () == "tunnel" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< tunnel_type > r (
+        tunnel_traits::create (i, f, this));
+
+      this->tunnel_.push_back (::std::move (r));
+      continue;
+    }
+
+    // bridge
+    //
+    if (n.name () == "bridge" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< bridge_type > r (
+        bridge_traits::create (i, f, this));
+
+      this->bridge_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+objects* objects::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class objects (*this, f, c);
+}
+
+objects& objects::
+operator= (const objects& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->object_ = x.object_;
+    this->objectReference_ = x.objectReference_;
+    this->tunnel_ = x.tunnel_;
+    this->bridge_ = x.bridge_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+objects::
+~objects ()
+{
+}
+
+// signals
+//
+
+signals::
+signals ()
+: ::xml_schema::type (),
+  signal_ (this),
+  signalReference_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+signals::
+signals (const signals& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  signal_ (x.signal_, f, this),
+  signalReference_ (x.signalReference_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+signals::
+signals (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  signal_ (this),
+  signalReference_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void signals::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // signal
+    //
+    if (n.name () == "signal" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< signal_type > r (
+        signal_traits::create (i, f, this));
+
+      this->signal_.push_back (::std::move (r));
+      continue;
+    }
+
+    // signalReference
+    //
+    if (n.name () == "signalReference" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< signalReference_type > r (
+        signalReference_traits::create (i, f, this));
+
+      this->signalReference_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+signals* signals::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class signals (*this, f, c);
+}
+
+signals& signals::
+operator= (const signals& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->signal_ = x.signal_;
+    this->signalReference_ = x.signalReference_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+signals::
+~signals ()
+{
+}
+
+// surface
+//
+
+surface::
+surface ()
+: ::xml_schema::type (),
+  CRG_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+surface::
+surface (const surface& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  CRG_ (x.CRG_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+surface::
+surface (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  CRG_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void surface::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // CRG
+    //
+    if (n.name () == "CRG" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< CRG_type > r (
+        CRG_traits::create (i, f, this));
+
+      this->CRG_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+surface* surface::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class surface (*this, f, c);
+}
+
+surface& surface::
+operator= (const surface& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->CRG_ = x.CRG_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+surface::
+~surface ()
+{
+}
+
+// railroad
+//
+
+railroad::
+railroad ()
+: ::xml_schema::type (),
+  switch__ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+railroad::
+railroad (const railroad& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  switch__ (x.switch__, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+railroad::
+railroad (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  switch__ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void railroad::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // switch
+    //
+    if (n.name () == "switch" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< switch_type > r (
+        switch_traits::create (i, f, this));
+
+      this->switch__.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+railroad* railroad::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class railroad (*this, f, c);
+}
+
+railroad& railroad::
+operator= (const railroad& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->switch__ = x.switch__;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+railroad::
+~railroad ()
+{
+}
+
+// control
+//
+
+control::
+control ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  signalId_ (this),
+  type_ (this)
+{
+}
+
+control::
+control (const control& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  signalId_ (x.signalId_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+control::
+control (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  signalId_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void control::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "signalId" && n.namespace_ ().empty ())
+    {
+      this->signalId_.set (signalId_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+control* control::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class control (*this, f, c);
+}
+
+control& control::
+operator= (const control& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->signalId_ = x.signalId_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+control::
+~control ()
+{
+}
+
+// connection
+//
+
+connection::
+connection ()
+: ::xml_schema::type (),
+  laneLink_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  incomingRoad_ (this),
+  connectingRoad_ (this),
+  contactPoint_ (this)
+{
+}
+
+connection::
+connection (const connection& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  laneLink_ (x.laneLink_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  incomingRoad_ (x.incomingRoad_, f, this),
+  connectingRoad_ (x.connectingRoad_, f, this),
+  contactPoint_ (x.contactPoint_, f, this)
+{
+}
+
+connection::
+connection (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  laneLink_ (this),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  incomingRoad_ (this),
+  connectingRoad_ (this),
+  contactPoint_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void connection::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // laneLink
+    //
+    if (n.name () == "laneLink" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< laneLink_type > r (
+        laneLink_traits::create (i, f, this));
+
+      this->laneLink_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "incomingRoad" && n.namespace_ ().empty ())
+    {
+      this->incomingRoad_.set (incomingRoad_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "connectingRoad" && n.namespace_ ().empty ())
+    {
+      this->connectingRoad_.set (connectingRoad_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "contactPoint" && n.namespace_ ().empty ())
+    {
+      this->contactPoint_.set (contactPoint_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+connection* connection::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class connection (*this, f, c);
+}
+
+connection& connection::
+operator= (const connection& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->laneLink_ = x.laneLink_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->incomingRoad_ = x.incomingRoad_;
+    this->connectingRoad_ = x.connectingRoad_;
+    this->contactPoint_ = x.contactPoint_;
+  }
+
+  return *this;
+}
+
+connection::
+~connection ()
+{
+}
+
+// priority
+//
+
+priority::
+priority ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  high_ (this),
+  low_ (this)
+{
+}
+
+priority::
+priority (const priority& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  high_ (x.high_, f, this),
+  low_ (x.low_, f, this)
+{
+}
+
+priority::
+priority (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  high_ (this),
+  low_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void priority::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "high" && n.namespace_ ().empty ())
+    {
+      this->high_.set (high_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "low" && n.namespace_ ().empty ())
+    {
+      this->low_.set (low_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+priority* priority::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class priority (*this, f, c);
+}
+
+priority& priority::
+operator= (const priority& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->high_ = x.high_;
+    this->low_ = x.low_;
+  }
+
+  return *this;
+}
+
+priority::
+~priority ()
+{
+}
+
+// controller1
+//
+
+controller1::
+controller1 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  sequence_ (this)
+{
+}
+
+controller1::
+controller1 (const controller1& x,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this),
+  sequence_ (x.sequence_, f, this)
+{
+}
+
+controller1::
+controller1 (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this),
+  sequence_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void controller1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sequence" && n.namespace_ ().empty ())
+    {
+      this->sequence_.set (sequence_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+controller1* controller1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class controller1 (*this, f, c);
+}
+
+controller1& controller1::
+operator= (const controller1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+    this->sequence_ = x.sequence_;
+  }
+
+  return *this;
+}
+
+controller1::
+~controller1 ()
+{
+}
+
+// junctionReference
+//
+
+junctionReference::
+junctionReference ()
+: ::xml_schema::type (),
+  junction_ (this)
+{
+}
+
+junctionReference::
+junctionReference (const junctionReference& x,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  junction_ (x.junction_, f, this)
+{
+}
+
+junctionReference::
+junctionReference (const ::xercesc::DOMElement& e,
+                   ::xml_schema::flags f,
+                   ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  junction_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void junctionReference::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "junction" && n.namespace_ ().empty ())
+    {
+      this->junction_.set (junction_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+junctionReference* junctionReference::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class junctionReference (*this, f, c);
+}
+
+junctionReference& junctionReference::
+operator= (const junctionReference& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->junction_ = x.junction_;
+  }
+
+  return *this;
+}
+
+junctionReference::
+~junctionReference ()
+{
+}
+
+// platform
+//
+
+platform::
+platform ()
+: ::xml_schema::type (),
+  segment_ (this),
+  name_ (this),
+  id_ (this)
+{
+}
+
+platform::
+platform (const platform& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  segment_ (x.segment_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this)
+{
+}
+
+platform::
+platform (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  segment_ (this),
+  name_ (this),
+  id_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void platform::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // segment
+    //
+    if (n.name () == "segment" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< segment_type > r (
+        segment_traits::create (i, f, this));
+
+      this->segment_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+platform* platform::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class platform (*this, f, c);
+}
+
+platform& platform::
+operator= (const platform& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->segment_ = x.segment_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+  }
+
+  return *this;
+}
+
+platform::
+~platform ()
+{
+}
+
+// line
+//
+
+line::
+line ()
+: ::xml_schema::type (),
+  length_ (this),
+  space_ (this),
+  tOffset_ (this),
+  sOffset_ (this),
+  rule_ (this),
+  width_ (this)
+{
+}
+
+line::
+line (const line& x,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  length_ (x.length_, f, this),
+  space_ (x.space_, f, this),
+  tOffset_ (x.tOffset_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  rule_ (x.rule_, f, this),
+  width_ (x.width_, f, this)
+{
+}
+
+line::
+line (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  length_ (this),
+  space_ (this),
+  tOffset_ (this),
+  sOffset_ (this),
+  rule_ (this),
+  width_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void line::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "space" && n.namespace_ ().empty ())
+    {
+      this->space_.set (space_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "tOffset" && n.namespace_ ().empty ())
+    {
+      this->tOffset_.set (tOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "rule" && n.namespace_ ().empty ())
+    {
+      this->rule_.set (rule_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+line* line::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class line (*this, f, c);
+}
+
+line& line::
+operator= (const line& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->length_ = x.length_;
+    this->space_ = x.space_;
+    this->tOffset_ = x.tOffset_;
+    this->sOffset_ = x.sOffset_;
+    this->rule_ = x.rule_;
+    this->width_ = x.width_;
+  }
+
+  return *this;
+}
+
+line::
+~line ()
+{
+}
+
+// predecessor1
+//
+
+predecessor1::
+predecessor1 ()
+: ::xml_schema::type (),
+  elementType_ (this),
+  elementId_ (this),
+  contactPoint_ (this)
+{
+}
+
+predecessor1::
+predecessor1 (const predecessor1& x,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  elementType_ (x.elementType_, f, this),
+  elementId_ (x.elementId_, f, this),
+  contactPoint_ (x.contactPoint_, f, this)
+{
+}
+
+predecessor1::
+predecessor1 (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f,
+              ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  elementType_ (this),
+  elementId_ (this),
+  contactPoint_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void predecessor1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "elementType" && n.namespace_ ().empty ())
+    {
+      this->elementType_.set (elementType_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "elementId" && n.namespace_ ().empty ())
+    {
+      this->elementId_.set (elementId_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "contactPoint" && n.namespace_ ().empty ())
+    {
+      this->contactPoint_.set (contactPoint_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+predecessor1* predecessor1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class predecessor1 (*this, f, c);
+}
+
+predecessor1& predecessor1::
+operator= (const predecessor1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->elementType_ = x.elementType_;
+    this->elementId_ = x.elementId_;
+    this->contactPoint_ = x.contactPoint_;
+  }
+
+  return *this;
+}
+
+predecessor1::
+~predecessor1 ()
+{
+}
+
+// successor1
+//
+
+successor1::
+successor1 ()
+: ::xml_schema::type (),
+  elementType_ (this),
+  elementId_ (this),
+  contactPoint_ (this)
+{
+}
+
+successor1::
+successor1 (const successor1& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  elementType_ (x.elementType_, f, this),
+  elementId_ (x.elementId_, f, this),
+  contactPoint_ (x.contactPoint_, f, this)
+{
+}
+
+successor1::
+successor1 (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  elementType_ (this),
+  elementId_ (this),
+  contactPoint_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void successor1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "elementType" && n.namespace_ ().empty ())
+    {
+      this->elementType_.set (elementType_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "elementId" && n.namespace_ ().empty ())
+    {
+      this->elementId_.set (elementId_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "contactPoint" && n.namespace_ ().empty ())
+    {
+      this->contactPoint_.set (contactPoint_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+successor1* successor1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class successor1 (*this, f, c);
+}
+
+successor1& successor1::
+operator= (const successor1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->elementType_ = x.elementType_;
+    this->elementId_ = x.elementId_;
+    this->contactPoint_ = x.contactPoint_;
+  }
+
+  return *this;
+}
+
+successor1::
+~successor1 ()
+{
+}
+
+// neighbor
+//
+
+neighbor::
+neighbor ()
+: ::xml_schema::type (),
+  side_ (this),
+  elementId_ (this),
+  direction_ (this)
+{
+}
+
+neighbor::
+neighbor (const neighbor& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  side_ (x.side_, f, this),
+  elementId_ (x.elementId_, f, this),
+  direction_ (x.direction_, f, this)
+{
+}
+
+neighbor::
+neighbor (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  side_ (this),
+  elementId_ (this),
+  direction_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void neighbor::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "side" && n.namespace_ ().empty ())
+    {
+      this->side_.set (side_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "elementId" && n.namespace_ ().empty ())
+    {
+      this->elementId_.set (elementId_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "direction" && n.namespace_ ().empty ())
+    {
+      this->direction_.set (direction_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+neighbor* neighbor::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class neighbor (*this, f, c);
+}
+
+neighbor& neighbor::
+operator= (const neighbor& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->side_ = x.side_;
+    this->elementId_ = x.elementId_;
+    this->direction_ = x.direction_;
+  }
+
+  return *this;
+}
+
+neighbor::
+~neighbor ()
+{
+}
+
+// speed1
+//
+
+speed1::
+speed1 ()
+: ::xml_schema::type (),
+  max_ (this),
+  unit_ (this)
+{
+}
+
+speed1::
+speed1 (const speed1& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  max_ (x.max_, f, this),
+  unit_ (x.unit_, f, this)
+{
+}
+
+speed1::
+speed1 (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  max_ (this),
+  unit_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void speed1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "max" && n.namespace_ ().empty ())
+    {
+      this->max_.set (max_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "unit" && n.namespace_ ().empty ())
+    {
+      this->unit_.set (unit_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+speed1* speed1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class speed1 (*this, f, c);
+}
+
+speed1& speed1::
+operator= (const speed1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->max_ = x.max_;
+    this->unit_ = x.unit_;
+  }
+
+  return *this;
+}
+
+speed1::
+~speed1 ()
+{
+}
+
+// geometry
+//
+
+geometry::
+geometry ()
+: ::xml_schema::type (),
+  line_ (this),
+  spiral_ (this),
+  arc_ (this),
+  poly3_ (this),
+  paramPoly3_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  x_ (this),
+  y_ (this),
+  hdg_ (this),
+  length_ (this)
+{
+}
+
+geometry::
+geometry (const geometry& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  line_ (x.line_, f, this),
+  spiral_ (x.spiral_, f, this),
+  arc_ (x.arc_, f, this),
+  poly3_ (x.poly3_, f, this),
+  paramPoly3_ (x.paramPoly3_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  x_ (x.x_, f, this),
+  y_ (x.y_, f, this),
+  hdg_ (x.hdg_, f, this),
+  length_ (x.length_, f, this)
+{
+}
+
+geometry::
+geometry (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  line_ (this),
+  spiral_ (this),
+  arc_ (this),
+  poly3_ (this),
+  paramPoly3_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  x_ (this),
+  y_ (this),
+  hdg_ (this),
+  length_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void geometry::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // line
+    //
+    if (n.name () == "line" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< line_type > r (
+        line_traits::create (i, f, this));
+
+      if (!this->line_)
+      {
+        this->line_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // spiral
+    //
+    if (n.name () == "spiral" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< spiral_type > r (
+        spiral_traits::create (i, f, this));
+
+      if (!this->spiral_)
+      {
+        this->spiral_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // arc
+    //
+    if (n.name () == "arc" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< arc_type > r (
+        arc_traits::create (i, f, this));
+
+      if (!this->arc_)
+      {
+        this->arc_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // poly3
+    //
+    if (n.name () == "poly3" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< poly3_type > r (
+        poly3_traits::create (i, f, this));
+
+      if (!this->poly3_)
+      {
+        this->poly3_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // paramPoly3
+    //
+    if (n.name () == "paramPoly3" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< paramPoly3_type > r (
+        paramPoly3_traits::create (i, f, this));
+
+      if (!this->paramPoly3_)
+      {
+        this->paramPoly3_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "x" && n.namespace_ ().empty ())
+    {
+      this->x_.set (x_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "y" && n.namespace_ ().empty ())
+    {
+      this->y_.set (y_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "hdg" && n.namespace_ ().empty ())
+    {
+      this->hdg_.set (hdg_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+geometry* geometry::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class geometry (*this, f, c);
+}
+
+geometry& geometry::
+operator= (const geometry& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->line_ = x.line_;
+    this->spiral_ = x.spiral_;
+    this->arc_ = x.arc_;
+    this->poly3_ = x.poly3_;
+    this->paramPoly3_ = x.paramPoly3_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->x_ = x.x_;
+    this->y_ = x.y_;
+    this->hdg_ = x.hdg_;
+    this->length_ = x.length_;
+  }
+
+  return *this;
+}
+
+geometry::
+~geometry ()
+{
+}
+
+// elevation
+//
+
+elevation::
+elevation ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+elevation::
+elevation (const elevation& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+elevation::
+elevation (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void elevation::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+elevation* elevation::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class elevation (*this, f, c);
+}
+
+elevation& elevation::
+operator= (const elevation& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+elevation::
+~elevation ()
+{
+}
+
+// superelevation
+//
+
+superelevation::
+superelevation ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+superelevation::
+superelevation (const superelevation& x,
+                ::xml_schema::flags f,
+                ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+superelevation::
+superelevation (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f,
+                ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void superelevation::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+superelevation* superelevation::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class superelevation (*this, f, c);
+}
+
+superelevation& superelevation::
+operator= (const superelevation& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+superelevation::
+~superelevation ()
+{
+}
+
+// crossfall
+//
+
+crossfall::
+crossfall ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  side_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+crossfall::
+crossfall (const crossfall& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  side_ (x.side_, f, this),
+  s_ (x.s_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+crossfall::
+crossfall (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  side_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void crossfall::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "side" && n.namespace_ ().empty ())
+    {
+      this->side_.set (side_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+crossfall* crossfall::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class crossfall (*this, f, c);
+}
+
+crossfall& crossfall::
+operator= (const crossfall& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->side_ = x.side_;
+    this->s_ = x.s_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+crossfall::
+~crossfall ()
+{
+}
+
+// shape
+//
+
+shape::
+shape ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+shape::
+shape (const shape& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+shape::
+shape (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void shape::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+shape* shape::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class shape (*this, f, c);
+}
+
+shape& shape::
+operator= (const shape& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+shape::
+~shape ()
+{
+}
+
+// laneOffset
+//
+
+laneOffset::
+laneOffset ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+laneOffset::
+laneOffset (const laneOffset& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+laneOffset::
+laneOffset (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void laneOffset::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+laneOffset* laneOffset::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneOffset (*this, f, c);
+}
+
+laneOffset& laneOffset::
+operator= (const laneOffset& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+laneOffset::
+~laneOffset ()
+{
+}
+
+// laneSection
+//
+
+laneSection::
+laneSection (const center_type& center)
+: ::xml_schema::type (),
+  left_ (this),
+  center_ (center, this),
+  right_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  singleSide_ (this)
+{
+}
+
+laneSection::
+laneSection (::std::unique_ptr< center_type > center)
+: ::xml_schema::type (),
+  left_ (this),
+  center_ (std::move (center), this),
+  right_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  singleSide_ (this)
+{
+}
+
+laneSection::
+laneSection (const laneSection& x,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  left_ (x.left_, f, this),
+  center_ (x.center_, f, this),
+  right_ (x.right_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  singleSide_ (x.singleSide_, f, this)
+{
+}
+
+laneSection::
+laneSection (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  left_ (this),
+  center_ (this),
+  right_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  singleSide_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void laneSection::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // left
+    //
+    if (n.name () == "left" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< left_type > r (
+        left_traits::create (i, f, this));
+
+      if (!this->left_)
+      {
+        this->left_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // center
+    //
+    if (n.name () == "center" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< center_type > r (
+        center_traits::create (i, f, this));
+
+      if (!center_.present ())
+      {
+        this->center_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // right
+    //
+    if (n.name () == "right" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< right_type > r (
+        right_traits::create (i, f, this));
+
+      if (!this->right_)
+      {
+        this->right_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  if (!center_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "center",
+      "");
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "singleSide" && n.namespace_ ().empty ())
+    {
+      this->singleSide_.set (singleSide_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+laneSection* laneSection::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneSection (*this, f, c);
+}
+
+laneSection& laneSection::
+operator= (const laneSection& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->left_ = x.left_;
+    this->center_ = x.center_;
+    this->right_ = x.right_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->singleSide_ = x.singleSide_;
+  }
+
+  return *this;
+}
+
+laneSection::
+~laneSection ()
+{
+}
+
+// object
+//
+
+object::
+object ()
+: ::xml_schema::type (),
+  repeat_ (this),
+  outline_ (this),
+  material_ (this),
+  validity_ (this),
+  parkingSpace_ (this),
+  userData_ (this),
+  include_ (this),
+  type_ (this),
+  name_ (this),
+  id_ (this),
+  s_ (this),
+  t_ (this),
+  zOffset_ (this),
+  validLength_ (this),
+  orientation_ (this),
+  length_ (this),
+  width_ (this),
+  radius_ (this),
+  height_ (this),
+  hdg_ (this),
+  pitch_ (this),
+  roll_ (this)
+{
+}
+
+object::
+object (const object& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  repeat_ (x.repeat_, f, this),
+  outline_ (x.outline_, f, this),
+  material_ (x.material_, f, this),
+  validity_ (x.validity_, f, this),
+  parkingSpace_ (x.parkingSpace_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  type_ (x.type_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  zOffset_ (x.zOffset_, f, this),
+  validLength_ (x.validLength_, f, this),
+  orientation_ (x.orientation_, f, this),
+  length_ (x.length_, f, this),
+  width_ (x.width_, f, this),
+  radius_ (x.radius_, f, this),
+  height_ (x.height_, f, this),
+  hdg_ (x.hdg_, f, this),
+  pitch_ (x.pitch_, f, this),
+  roll_ (x.roll_, f, this)
+{
+}
+
+object::
+object (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  repeat_ (this),
+  outline_ (this),
+  material_ (this),
+  validity_ (this),
+  parkingSpace_ (this),
+  userData_ (this),
+  include_ (this),
+  type_ (this),
+  name_ (this),
+  id_ (this),
+  s_ (this),
+  t_ (this),
+  zOffset_ (this),
+  validLength_ (this),
+  orientation_ (this),
+  length_ (this),
+  width_ (this),
+  radius_ (this),
+  height_ (this),
+  hdg_ (this),
+  pitch_ (this),
+  roll_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void object::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // repeat
+    //
+    if (n.name () == "repeat" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< repeat_type > r (
+        repeat_traits::create (i, f, this));
+
+      this->repeat_.push_back (::std::move (r));
+      continue;
+    }
+
+    // outline
+    //
+    if (n.name () == "outline" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< outline_type > r (
+        outline_traits::create (i, f, this));
+
+      if (!this->outline_)
+      {
+        this->outline_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // material
+    //
+    if (n.name () == "material" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< material_type > r (
+        material_traits::create (i, f, this));
+
+      if (!this->material_)
+      {
+        this->material_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // parkingSpace
+    //
+    if (n.name () == "parkingSpace" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< parkingSpace_type > r (
+        parkingSpace_traits::create (i, f, this));
+
+      if (!this->parkingSpace_)
+      {
+        this->parkingSpace_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffset" && n.namespace_ ().empty ())
+    {
+      this->zOffset_.set (zOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "validLength" && n.namespace_ ().empty ())
+    {
+      this->validLength_.set (validLength_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "orientation" && n.namespace_ ().empty ())
+    {
+      this->orientation_.set (orientation_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "radius" && n.namespace_ ().empty ())
+    {
+      this->radius_.set (radius_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "hdg" && n.namespace_ ().empty ())
+    {
+      this->hdg_.set (hdg_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "pitch" && n.namespace_ ().empty ())
+    {
+      this->pitch_.set (pitch_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "roll" && n.namespace_ ().empty ())
+    {
+      this->roll_.set (roll_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+object* object::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class object (*this, f, c);
+}
+
+object& object::
+operator= (const object& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->repeat_ = x.repeat_;
+    this->outline_ = x.outline_;
+    this->material_ = x.material_;
+    this->validity_ = x.validity_;
+    this->parkingSpace_ = x.parkingSpace_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->type_ = x.type_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->zOffset_ = x.zOffset_;
+    this->validLength_ = x.validLength_;
+    this->orientation_ = x.orientation_;
+    this->length_ = x.length_;
+    this->width_ = x.width_;
+    this->radius_ = x.radius_;
+    this->height_ = x.height_;
+    this->hdg_ = x.hdg_;
+    this->pitch_ = x.pitch_;
+    this->roll_ = x.roll_;
+  }
+
+  return *this;
+}
+
+object::
+~object ()
+{
+}
+
+// objectReference
+//
+
+objectReference::
+objectReference ()
+: ::xml_schema::type (),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  zOffset_ (this),
+  validLength_ (this),
+  orientation_ (this)
+{
+}
+
+objectReference::
+objectReference (const objectReference& x,
+                 ::xml_schema::flags f,
+                 ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  validity_ (x.validity_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  id_ (x.id_, f, this),
+  zOffset_ (x.zOffset_, f, this),
+  validLength_ (x.validLength_, f, this),
+  orientation_ (x.orientation_, f, this)
+{
+}
+
+objectReference::
+objectReference (const ::xercesc::DOMElement& e,
+                 ::xml_schema::flags f,
+                 ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  zOffset_ (this),
+  validLength_ (this),
+  orientation_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void objectReference::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffset" && n.namespace_ ().empty ())
+    {
+      this->zOffset_.set (zOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "validLength" && n.namespace_ ().empty ())
+    {
+      this->validLength_.set (validLength_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "orientation" && n.namespace_ ().empty ())
+    {
+      this->orientation_.set (orientation_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+objectReference* objectReference::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class objectReference (*this, f, c);
+}
+
+objectReference& objectReference::
+operator= (const objectReference& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->validity_ = x.validity_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->id_ = x.id_;
+    this->zOffset_ = x.zOffset_;
+    this->validLength_ = x.validLength_;
+    this->orientation_ = x.orientation_;
+  }
+
+  return *this;
+}
+
+objectReference::
+~objectReference ()
+{
+}
+
+// tunnel
+//
+
+tunnel::
+tunnel ()
+: ::xml_schema::type (),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this),
+  lighting_ (this),
+  daylight_ (this)
+{
+}
+
+tunnel::
+tunnel (const tunnel& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  validity_ (x.validity_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  length_ (x.length_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this),
+  lighting_ (x.lighting_, f, this),
+  daylight_ (x.daylight_, f, this)
+{
+}
+
+tunnel::
+tunnel (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this),
+  lighting_ (this),
+  daylight_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void tunnel::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "lighting" && n.namespace_ ().empty ())
+    {
+      this->lighting_.set (lighting_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "daylight" && n.namespace_ ().empty ())
+    {
+      this->daylight_.set (daylight_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+tunnel* tunnel::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class tunnel (*this, f, c);
+}
+
+tunnel& tunnel::
+operator= (const tunnel& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->validity_ = x.validity_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->length_ = x.length_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+    this->lighting_ = x.lighting_;
+    this->daylight_ = x.daylight_;
+  }
+
+  return *this;
+}
+
+tunnel::
+~tunnel ()
+{
+}
+
+// bridge
+//
+
+bridge::
+bridge ()
+: ::xml_schema::type (),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+}
+
+bridge::
+bridge (const bridge& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  validity_ (x.validity_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  length_ (x.length_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+bridge::
+bridge (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  name_ (this),
+  id_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void bridge::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+bridge* bridge::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class bridge (*this, f, c);
+}
+
+bridge& bridge::
+operator= (const bridge& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->validity_ = x.validity_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->length_ = x.length_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+bridge::
+~bridge ()
+{
+}
+
+// signal
+//
+
+signal::
+signal ()
+: ::xml_schema::type (),
+  validity_ (this),
+  dependency_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  name_ (this),
+  dynamic_ (this),
+  orientation_ (this),
+  zOffset_ (this),
+  country_ (this),
+  type_ (this),
+  subtype_ (this),
+  value_ (this),
+  unit_ (this),
+  height_ (this),
+  width_ (this),
+  text_ (this),
+  hOffset_ (this),
+  pitch_ (this),
+  roll_ (this)
+{
+}
+
+signal::
+signal (const signal& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  validity_ (x.validity_, f, this),
+  dependency_ (x.dependency_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  id_ (x.id_, f, this),
+  name_ (x.name_, f, this),
+  dynamic_ (x.dynamic_, f, this),
+  orientation_ (x.orientation_, f, this),
+  zOffset_ (x.zOffset_, f, this),
+  country_ (x.country_, f, this),
+  type_ (x.type_, f, this),
+  subtype_ (x.subtype_, f, this),
+  value_ (x.value_, f, this),
+  unit_ (x.unit_, f, this),
+  height_ (x.height_, f, this),
+  width_ (x.width_, f, this),
+  text_ (x.text_, f, this),
+  hOffset_ (x.hOffset_, f, this),
+  pitch_ (x.pitch_, f, this),
+  roll_ (x.roll_, f, this)
+{
+}
+
+signal::
+signal (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  validity_ (this),
+  dependency_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  name_ (this),
+  dynamic_ (this),
+  orientation_ (this),
+  zOffset_ (this),
+  country_ (this),
+  type_ (this),
+  subtype_ (this),
+  value_ (this),
+  unit_ (this),
+  height_ (this),
+  width_ (this),
+  text_ (this),
+  hOffset_ (this),
+  pitch_ (this),
+  roll_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void signal::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // dependency
+    //
+    if (n.name () == "dependency" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< dependency_type > r (
+        dependency_traits::create (i, f, this));
+
+      this->dependency_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dynamic" && n.namespace_ ().empty ())
+    {
+      this->dynamic_.set (dynamic_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "orientation" && n.namespace_ ().empty ())
+    {
+      this->orientation_.set (orientation_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffset" && n.namespace_ ().empty ())
+    {
+      this->zOffset_.set (zOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "country" && n.namespace_ ().empty ())
+    {
+      this->country_.set (country_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "subtype" && n.namespace_ ().empty ())
+    {
+      this->subtype_.set (subtype_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "value" && n.namespace_ ().empty ())
+    {
+      this->value_.set (value_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "unit" && n.namespace_ ().empty ())
+    {
+      this->unit_.set (unit_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "width" && n.namespace_ ().empty ())
+    {
+      this->width_.set (width_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "text" && n.namespace_ ().empty ())
+    {
+      this->text_.set (text_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "hOffset" && n.namespace_ ().empty ())
+    {
+      this->hOffset_.set (hOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "pitch" && n.namespace_ ().empty ())
+    {
+      this->pitch_.set (pitch_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "roll" && n.namespace_ ().empty ())
+    {
+      this->roll_.set (roll_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+signal* signal::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class signal (*this, f, c);
+}
+
+signal& signal::
+operator= (const signal& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->validity_ = x.validity_;
+    this->dependency_ = x.dependency_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->id_ = x.id_;
+    this->name_ = x.name_;
+    this->dynamic_ = x.dynamic_;
+    this->orientation_ = x.orientation_;
+    this->zOffset_ = x.zOffset_;
+    this->country_ = x.country_;
+    this->type_ = x.type_;
+    this->subtype_ = x.subtype_;
+    this->value_ = x.value_;
+    this->unit_ = x.unit_;
+    this->height_ = x.height_;
+    this->width_ = x.width_;
+    this->text_ = x.text_;
+    this->hOffset_ = x.hOffset_;
+    this->pitch_ = x.pitch_;
+    this->roll_ = x.roll_;
+  }
+
+  return *this;
+}
+
+signal::
+~signal ()
+{
+}
+
+// signalReference
+//
+
+signalReference::
+signalReference ()
+: ::xml_schema::type (),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  orientation_ (this)
+{
+}
+
+signalReference::
+signalReference (const signalReference& x,
+                 ::xml_schema::flags f,
+                 ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  validity_ (x.validity_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  id_ (x.id_, f, this),
+  orientation_ (x.orientation_, f, this)
+{
+}
+
+signalReference::
+signalReference (const ::xercesc::DOMElement& e,
+                 ::xml_schema::flags f,
+                 ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  validity_ (this),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  id_ (this),
+  orientation_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void signalReference::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // validity
+    //
+    if (n.name () == "validity" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< validity_type > r (
+        validity_traits::create (i, f, this));
+
+      this->validity_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "orientation" && n.namespace_ ().empty ())
+    {
+      this->orientation_.set (orientation_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+signalReference* signalReference::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class signalReference (*this, f, c);
+}
+
+signalReference& signalReference::
+operator= (const signalReference& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->validity_ = x.validity_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->id_ = x.id_;
+    this->orientation_ = x.orientation_;
+  }
+
+  return *this;
+}
+
+signalReference::
+~signalReference ()
+{
+}
+
+// CRG
+//
+
+CRG::
+CRG ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  file_ (this),
+  sStart_ (this),
+  sEnd_ (this),
+  orientation_ (this),
+  mode_ (this),
+  purpose_ (this),
+  sOffset_ (this),
+  tOffset_ (this),
+  zOffset_ (this),
+  zScale_ (this),
+  hOffset_ (this)
+{
+}
+
+CRG::
+CRG (const CRG& x,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  file_ (x.file_, f, this),
+  sStart_ (x.sStart_, f, this),
+  sEnd_ (x.sEnd_, f, this),
+  orientation_ (x.orientation_, f, this),
+  mode_ (x.mode_, f, this),
+  purpose_ (x.purpose_, f, this),
+  sOffset_ (x.sOffset_, f, this),
+  tOffset_ (x.tOffset_, f, this),
+  zOffset_ (x.zOffset_, f, this),
+  zScale_ (x.zScale_, f, this),
+  hOffset_ (x.hOffset_, f, this)
+{
+}
+
+CRG::
+CRG (const ::xercesc::DOMElement& e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  file_ (this),
+  sStart_ (this),
+  sEnd_ (this),
+  orientation_ (this),
+  mode_ (this),
+  purpose_ (this),
+  sOffset_ (this),
+  tOffset_ (this),
+  zOffset_ (this),
+  zScale_ (this),
+  hOffset_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void CRG::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "file" && n.namespace_ ().empty ())
+    {
+      this->file_.set (file_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sStart" && n.namespace_ ().empty ())
+    {
+      this->sStart_.set (sStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sEnd" && n.namespace_ ().empty ())
+    {
+      this->sEnd_.set (sEnd_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "orientation" && n.namespace_ ().empty ())
+    {
+      this->orientation_.set (orientation_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "mode" && n.namespace_ ().empty ())
+    {
+      this->mode_.set (mode_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "purpose" && n.namespace_ ().empty ())
+    {
+      this->purpose_.set (purpose_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sOffset" && n.namespace_ ().empty ())
+    {
+      this->sOffset_.set (sOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "tOffset" && n.namespace_ ().empty ())
+    {
+      this->tOffset_.set (tOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffset" && n.namespace_ ().empty ())
+    {
+      this->zOffset_.set (zOffset_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zScale" && n.namespace_ ().empty ())
+    {
+      this->zScale_.set (zScale_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "hOffset" && n.namespace_ ().empty ())
+    {
+      this->hOffset_.set (hOffset_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+CRG* CRG::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class CRG (*this, f, c);
+}
+
+CRG& CRG::
+operator= (const CRG& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->file_ = x.file_;
+    this->sStart_ = x.sStart_;
+    this->sEnd_ = x.sEnd_;
+    this->orientation_ = x.orientation_;
+    this->mode_ = x.mode_;
+    this->purpose_ = x.purpose_;
+    this->sOffset_ = x.sOffset_;
+    this->tOffset_ = x.tOffset_;
+    this->zOffset_ = x.zOffset_;
+    this->zScale_ = x.zScale_;
+    this->hOffset_ = x.hOffset_;
+  }
+
+  return *this;
+}
+
+CRG::
+~CRG ()
+{
+}
+
+// switch_
+//
+
+switch_::
+switch_ (const mainTrack_type& mainTrack,
+         const sideTrack_type& sideTrack)
+: ::xml_schema::type (),
+  mainTrack_ (mainTrack, this),
+  sideTrack_ (sideTrack, this),
+  partner_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  position_ (this)
+{
+}
+
+switch_::
+switch_ (::std::unique_ptr< mainTrack_type > mainTrack,
+         ::std::unique_ptr< sideTrack_type > sideTrack)
+: ::xml_schema::type (),
+  mainTrack_ (std::move (mainTrack), this),
+  sideTrack_ (std::move (sideTrack), this),
+  partner_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  position_ (this)
+{
+}
+
+switch_::
+switch_ (const switch_& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  mainTrack_ (x.mainTrack_, f, this),
+  sideTrack_ (x.sideTrack_, f, this),
+  partner_ (x.partner_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this),
+  position_ (x.position_, f, this)
+{
+}
+
+switch_::
+switch_ (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  mainTrack_ (this),
+  sideTrack_ (this),
+  partner_ (this),
+  userData_ (this),
+  include_ (this),
+  name_ (this),
+  id_ (this),
+  position_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void switch_::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // mainTrack
+    //
+    if (n.name () == "mainTrack" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< mainTrack_type > r (
+        mainTrack_traits::create (i, f, this));
+
+      if (!mainTrack_.present ())
+      {
+        this->mainTrack_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // sideTrack
+    //
+    if (n.name () == "sideTrack" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< sideTrack_type > r (
+        sideTrack_traits::create (i, f, this));
+
+      if (!sideTrack_.present ())
+      {
+        this->sideTrack_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // partner
+    //
+    if (n.name () == "partner" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< partner_type > r (
+        partner_traits::create (i, f, this));
+
+      if (!this->partner_)
+      {
+        this->partner_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  if (!mainTrack_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "mainTrack",
+      "");
+  }
+
+  if (!sideTrack_.present ())
+  {
+    throw ::xsd::cxx::tree::expected_element< char > (
+      "sideTrack",
+      "");
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "position" && n.namespace_ ().empty ())
+    {
+      this->position_.set (position_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+switch_* switch_::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class switch_ (*this, f, c);
+}
+
+switch_& switch_::
+operator= (const switch_& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->mainTrack_ = x.mainTrack_;
+    this->sideTrack_ = x.sideTrack_;
+    this->partner_ = x.partner_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+    this->position_ = x.position_;
+  }
+
+  return *this;
+}
+
+switch_::
+~switch_ ()
+{
+}
+
+// laneLink
+//
+
+laneLink::
+laneLink ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  from_ (this),
+  to_ (this)
+{
+}
+
+laneLink::
+laneLink (const laneLink& x,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  from_ (x.from_, f, this),
+  to_ (x.to_, f, this)
+{
+}
+
+laneLink::
+laneLink (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f,
+          ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  from_ (this),
+  to_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void laneLink::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "from" && n.namespace_ ().empty ())
+    {
+      this->from_.set (from_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "to" && n.namespace_ ().empty ())
+    {
+      this->to_.set (to_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+laneLink* laneLink::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class laneLink (*this, f, c);
+}
+
+laneLink& laneLink::
+operator= (const laneLink& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->from_ = x.from_;
+    this->to_ = x.to_;
+  }
+
+  return *this;
+}
+
+laneLink::
+~laneLink ()
+{
+}
+
+// segment
+//
+
+segment::
+segment ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  roadId_ (this),
+  sStart_ (this),
+  sEnd_ (this),
+  side_ (this)
+{
+}
+
+segment::
+segment (const segment& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  roadId_ (x.roadId_, f, this),
+  sStart_ (x.sStart_, f, this),
+  sEnd_ (x.sEnd_, f, this),
+  side_ (x.side_, f, this)
+{
+}
+
+segment::
+segment (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  roadId_ (this),
+  sStart_ (this),
+  sEnd_ (this),
+  side_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void segment::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "roadId" && n.namespace_ ().empty ())
+    {
+      this->roadId_.set (roadId_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sStart" && n.namespace_ ().empty ())
+    {
+      this->sStart_.set (sStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "sEnd" && n.namespace_ ().empty ())
+    {
+      this->sEnd_.set (sEnd_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "side" && n.namespace_ ().empty ())
+    {
+      this->side_.set (side_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+segment* segment::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class segment (*this, f, c);
+}
+
+segment& segment::
+operator= (const segment& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->roadId_ = x.roadId_;
+    this->sStart_ = x.sStart_;
+    this->sEnd_ = x.sEnd_;
+    this->side_ = x.side_;
+  }
+
+  return *this;
+}
+
+segment::
+~segment ()
+{
+}
+
+// line1
+//
+
+line1::
+line1 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+line1::
+line1 (const line1& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+line1::
+line1 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void line1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+line1* line1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class line1 (*this, f, c);
+}
+
+line1& line1::
+operator= (const line1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+line1::
+~line1 ()
+{
+}
+
+// spiral
+//
+
+spiral::
+spiral ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  curvStart_ (this),
+  curvEnd_ (this)
+{
+}
+
+spiral::
+spiral (const spiral& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  curvStart_ (x.curvStart_, f, this),
+  curvEnd_ (x.curvEnd_, f, this)
+{
+}
+
+spiral::
+spiral (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  curvStart_ (this),
+  curvEnd_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void spiral::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "curvStart" && n.namespace_ ().empty ())
+    {
+      this->curvStart_.set (curvStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "curvEnd" && n.namespace_ ().empty ())
+    {
+      this->curvEnd_.set (curvEnd_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+spiral* spiral::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class spiral (*this, f, c);
+}
+
+spiral& spiral::
+operator= (const spiral& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->curvStart_ = x.curvStart_;
+    this->curvEnd_ = x.curvEnd_;
+  }
+
+  return *this;
+}
+
+spiral::
+~spiral ()
+{
+}
+
+// arc
+//
+
+arc::
+arc ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  curvature_ (this)
+{
+}
+
+arc::
+arc (const arc& x,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  curvature_ (x.curvature_, f, this)
+{
+}
+
+arc::
+arc (const ::xercesc::DOMElement& e,
+     ::xml_schema::flags f,
+     ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  curvature_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void arc::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "curvature" && n.namespace_ ().empty ())
+    {
+      this->curvature_.set (curvature_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+arc* arc::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class arc (*this, f, c);
+}
+
+arc& arc::
+operator= (const arc& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->curvature_ = x.curvature_;
+  }
+
+  return *this;
+}
+
+arc::
+~arc ()
+{
+}
+
+// poly3
+//
+
+poly3::
+poly3 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+}
+
+poly3::
+poly3 (const poly3& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  a_ (x.a_, f, this),
+  b_ (x.b_, f, this),
+  c_ (x.c_, f, this),
+  d_ (x.d_, f, this)
+{
+}
+
+poly3::
+poly3 (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  a_ (this),
+  b_ (this),
+  c_ (this),
+  d_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void poly3::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "a" && n.namespace_ ().empty ())
+    {
+      this->a_.set (a_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "b" && n.namespace_ ().empty ())
+    {
+      this->b_.set (b_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "c" && n.namespace_ ().empty ())
+    {
+      this->c_.set (c_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "d" && n.namespace_ ().empty ())
+    {
+      this->d_.set (d_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+poly3* poly3::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class poly3 (*this, f, c);
+}
+
+poly3& poly3::
+operator= (const poly3& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->a_ = x.a_;
+    this->b_ = x.b_;
+    this->c_ = x.c_;
+    this->d_ = x.d_;
+  }
+
+  return *this;
+}
+
+poly3::
+~poly3 ()
+{
+}
+
+// paramPoly3
+//
+
+paramPoly3::
+paramPoly3 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  aU_ (this),
+  bU_ (this),
+  cU_ (this),
+  dU_ (this),
+  aV_ (this),
+  bV_ (this),
+  cV_ (this),
+  dV_ (this),
+  pRange_ (this)
+{
+}
+
+paramPoly3::
+paramPoly3 (const paramPoly3& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  aU_ (x.aU_, f, this),
+  bU_ (x.bU_, f, this),
+  cU_ (x.cU_, f, this),
+  dU_ (x.dU_, f, this),
+  aV_ (x.aV_, f, this),
+  bV_ (x.bV_, f, this),
+  cV_ (x.cV_, f, this),
+  dV_ (x.dV_, f, this),
+  pRange_ (x.pRange_, f, this)
+{
+}
+
+paramPoly3::
+paramPoly3 (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  aU_ (this),
+  bU_ (this),
+  cU_ (this),
+  dU_ (this),
+  aV_ (this),
+  bV_ (this),
+  cV_ (this),
+  dV_ (this),
+  pRange_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void paramPoly3::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "aU" && n.namespace_ ().empty ())
+    {
+      this->aU_.set (aU_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "bU" && n.namespace_ ().empty ())
+    {
+      this->bU_.set (bU_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "cU" && n.namespace_ ().empty ())
+    {
+      this->cU_.set (cU_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dU" && n.namespace_ ().empty ())
+    {
+      this->dU_.set (dU_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "aV" && n.namespace_ ().empty ())
+    {
+      this->aV_.set (aV_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "bV" && n.namespace_ ().empty ())
+    {
+      this->bV_.set (bV_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "cV" && n.namespace_ ().empty ())
+    {
+      this->cV_.set (cV_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dV" && n.namespace_ ().empty ())
+    {
+      this->dV_.set (dV_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "pRange" && n.namespace_ ().empty ())
+    {
+      this->pRange_.set (pRange_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+paramPoly3* paramPoly3::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class paramPoly3 (*this, f, c);
+}
+
+paramPoly3& paramPoly3::
+operator= (const paramPoly3& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->aU_ = x.aU_;
+    this->bU_ = x.bU_;
+    this->cU_ = x.cU_;
+    this->dU_ = x.dU_;
+    this->aV_ = x.aV_;
+    this->bV_ = x.bV_;
+    this->cV_ = x.cV_;
+    this->dV_ = x.dV_;
+    this->pRange_ = x.pRange_;
+  }
+
+  return *this;
+}
+
+paramPoly3::
+~paramPoly3 ()
+{
+}
+
+// left
+//
+
+left::
+left ()
+: ::xml_schema::type (),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+left::
+left (const left& x,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_ (x.lane_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+left::
+left (const ::xercesc::DOMElement& e,
+      ::xml_schema::flags f,
+      ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void left::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // lane
+    //
+    if (n.name () == "lane" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< lane_type > r (
+        lane_traits::create (i, f, this));
+
+      this->lane_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+left* left::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class left (*this, f, c);
+}
+
+left& left::
+operator= (const left& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_ = x.lane_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+left::
+~left ()
+{
+}
+
+// center
+//
+
+center::
+center ()
+: ::xml_schema::type (),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+center::
+center (const center& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_ (x.lane_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+center::
+center (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void center::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // lane
+    //
+    if (n.name () == "lane" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< lane_type > r (
+        lane_traits::create (i, f, this));
+
+      if (!this->lane_)
+      {
+        this->lane_.set (::std::move (r));
+        continue;
+      }
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+center* center::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class center (*this, f, c);
+}
+
+center& center::
+operator= (const center& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_ = x.lane_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+center::
+~center ()
+{
+}
+
+// right
+//
+
+right::
+right ()
+: ::xml_schema::type (),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+right::
+right (const right& x,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  lane_ (x.lane_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+right::
+right (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f,
+       ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  lane_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void right::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // lane
+    //
+    if (n.name () == "lane" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< lane_type > r (
+        lane_traits::create (i, f, this));
+
+      this->lane_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+right* right::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class right (*this, f, c);
+}
+
+right& right::
+operator= (const right& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->lane_ = x.lane_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+right::
+~right ()
+{
+}
+
+// repeat
+//
+
+repeat::
+repeat ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  distance_ (this),
+  tStart_ (this),
+  tEnd_ (this),
+  widthStart_ (this),
+  widthEnd_ (this),
+  heightStart_ (this),
+  heightEnd_ (this),
+  zOffsetStart_ (this),
+  zOffsetEnd_ (this)
+{
+}
+
+repeat::
+repeat (const repeat& x,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  length_ (x.length_, f, this),
+  distance_ (x.distance_, f, this),
+  tStart_ (x.tStart_, f, this),
+  tEnd_ (x.tEnd_, f, this),
+  widthStart_ (x.widthStart_, f, this),
+  widthEnd_ (x.widthEnd_, f, this),
+  heightStart_ (x.heightStart_, f, this),
+  heightEnd_ (x.heightEnd_, f, this),
+  zOffsetStart_ (x.zOffsetStart_, f, this),
+  zOffsetEnd_ (x.zOffsetEnd_, f, this)
+{
+}
+
+repeat::
+repeat (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f,
+        ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  length_ (this),
+  distance_ (this),
+  tStart_ (this),
+  tEnd_ (this),
+  widthStart_ (this),
+  widthEnd_ (this),
+  heightStart_ (this),
+  heightEnd_ (this),
+  zOffsetStart_ (this),
+  zOffsetEnd_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void repeat::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "length" && n.namespace_ ().empty ())
+    {
+      this->length_.set (length_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "distance" && n.namespace_ ().empty ())
+    {
+      this->distance_.set (distance_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "tStart" && n.namespace_ ().empty ())
+    {
+      this->tStart_.set (tStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "tEnd" && n.namespace_ ().empty ())
+    {
+      this->tEnd_.set (tEnd_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "widthStart" && n.namespace_ ().empty ())
+    {
+      this->widthStart_.set (widthStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "widthEnd" && n.namespace_ ().empty ())
+    {
+      this->widthEnd_.set (widthEnd_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "heightStart" && n.namespace_ ().empty ())
+    {
+      this->heightStart_.set (heightStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "heightEnd" && n.namespace_ ().empty ())
+    {
+      this->heightEnd_.set (heightEnd_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffsetStart" && n.namespace_ ().empty ())
+    {
+      this->zOffsetStart_.set (zOffsetStart_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "zOffsetEnd" && n.namespace_ ().empty ())
+    {
+      this->zOffsetEnd_.set (zOffsetEnd_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+repeat* repeat::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class repeat (*this, f, c);
+}
+
+repeat& repeat::
+operator= (const repeat& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->length_ = x.length_;
+    this->distance_ = x.distance_;
+    this->tStart_ = x.tStart_;
+    this->tEnd_ = x.tEnd_;
+    this->widthStart_ = x.widthStart_;
+    this->widthEnd_ = x.widthEnd_;
+    this->heightStart_ = x.heightStart_;
+    this->heightEnd_ = x.heightEnd_;
+    this->zOffsetStart_ = x.zOffsetStart_;
+    this->zOffsetEnd_ = x.zOffsetEnd_;
+  }
+
+  return *this;
+}
+
+repeat::
+~repeat ()
+{
+}
+
+// outline
+//
+
+outline::
+outline ()
+: ::xml_schema::type (),
+  cornerRoad_ (this),
+  cornerLocal_ (this),
+  userData_ (this),
+  include_ (this)
+{
+}
+
+outline::
+outline (const outline& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  cornerRoad_ (x.cornerRoad_, f, this),
+  cornerLocal_ (x.cornerLocal_, f, this),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this)
+{
+}
+
+outline::
+outline (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  cornerRoad_ (this),
+  cornerLocal_ (this),
+  userData_ (this),
+  include_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, false);
+    this->parse (p, f);
+  }
+}
+
+void outline::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // cornerRoad
+    //
+    if (n.name () == "cornerRoad" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< cornerRoad_type > r (
+        cornerRoad_traits::create (i, f, this));
+
+      this->cornerRoad_.push_back (::std::move (r));
+      continue;
+    }
+
+    // cornerLocal
+    //
+    if (n.name () == "cornerLocal" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< cornerLocal_type > r (
+        cornerLocal_traits::create (i, f, this));
+
+      this->cornerLocal_.push_back (::std::move (r));
+      continue;
+    }
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+}
+
+outline* outline::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class outline (*this, f, c);
+}
+
+outline& outline::
+operator= (const outline& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->cornerRoad_ = x.cornerRoad_;
+    this->cornerLocal_ = x.cornerLocal_;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+  }
+
+  return *this;
+}
+
+outline::
+~outline ()
+{
+}
+
+// material1
+//
+
+material1::
+material1 ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  surface_ (this),
+  friction_ (this),
+  roughness_ (this)
+{
+}
+
+material1::
+material1 (const material1& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  surface_ (x.surface_, f, this),
+  friction_ (x.friction_, f, this),
+  roughness_ (x.roughness_, f, this)
+{
+}
+
+material1::
+material1 (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  surface_ (this),
+  friction_ (this),
+  roughness_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void material1::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "surface" && n.namespace_ ().empty ())
+    {
+      this->surface_.set (surface_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "friction" && n.namespace_ ().empty ())
+    {
+      this->friction_.set (friction_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "roughness" && n.namespace_ ().empty ())
+    {
+      this->roughness_.set (roughness_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+material1* material1::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class material1 (*this, f, c);
+}
+
+material1& material1::
+operator= (const material1& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->surface_ = x.surface_;
+    this->friction_ = x.friction_;
+    this->roughness_ = x.roughness_;
+  }
+
+  return *this;
+}
+
+material1::
+~material1 ()
+{
+}
+
+// dependency
+//
+
+dependency::
+dependency ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this)
+{
+}
+
+dependency::
+dependency (const dependency& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  id_ (x.id_, f, this),
+  type_ (x.type_, f, this)
+{
+}
+
+dependency::
+dependency (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  id_ (this),
+  type_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void dependency::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "type" && n.namespace_ ().empty ())
+    {
+      this->type_.set (type_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+dependency* dependency::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class dependency (*this, f, c);
+}
+
+dependency& dependency::
+operator= (const dependency& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->id_ = x.id_;
+    this->type_ = x.type_;
+  }
+
+  return *this;
+}
+
+dependency::
+~dependency ()
+{
+}
+
+// mainTrack
+//
+
+mainTrack::
+mainTrack ()
+: ::xml_schema::type (),
+  id_ (this),
+  s_ (this),
+  dir_ (this)
+{
+}
+
+mainTrack::
+mainTrack (const mainTrack& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  id_ (x.id_, f, this),
+  s_ (x.s_, f, this),
+  dir_ (x.dir_, f, this)
+{
+}
+
+mainTrack::
+mainTrack (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  id_ (this),
+  s_ (this),
+  dir_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void mainTrack::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dir" && n.namespace_ ().empty ())
+    {
+      this->dir_.set (dir_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+mainTrack* mainTrack::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class mainTrack (*this, f, c);
+}
+
+mainTrack& mainTrack::
+operator= (const mainTrack& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->id_ = x.id_;
+    this->s_ = x.s_;
+    this->dir_ = x.dir_;
+  }
+
+  return *this;
+}
+
+mainTrack::
+~mainTrack ()
+{
+}
+
+// sideTrack
+//
+
+sideTrack::
+sideTrack ()
+: ::xml_schema::type (),
+  id_ (this),
+  s_ (this),
+  dir_ (this)
+{
+}
+
+sideTrack::
+sideTrack (const sideTrack& x,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  id_ (x.id_, f, this),
+  s_ (x.s_, f, this),
+  dir_ (x.dir_, f, this)
+{
+}
+
+sideTrack::
+sideTrack (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f,
+           ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  id_ (this),
+  s_ (this),
+  dir_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void sideTrack::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dir" && n.namespace_ ().empty ())
+    {
+      this->dir_.set (dir_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+sideTrack* sideTrack::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class sideTrack (*this, f, c);
+}
+
+sideTrack& sideTrack::
+operator= (const sideTrack& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->id_ = x.id_;
+    this->s_ = x.s_;
+    this->dir_ = x.dir_;
+  }
+
+  return *this;
+}
+
+sideTrack::
+~sideTrack ()
+{
+}
+
+// partner
+//
+
+partner::
+partner ()
+: ::xml_schema::type (),
+  name_ (this),
+  id_ (this)
+{
+}
+
+partner::
+partner (const partner& x,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  name_ (x.name_, f, this),
+  id_ (x.id_, f, this)
+{
+}
+
+partner::
+partner (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f,
+         ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  name_ (this),
+  id_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, false, false, true);
+    this->parse (p, f);
+  }
+}
+
+void partner::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "name" && n.namespace_ ().empty ())
+    {
+      this->name_.set (name_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "id" && n.namespace_ ().empty ())
+    {
+      this->id_.set (id_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+partner* partner::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class partner (*this, f, c);
+}
+
+partner& partner::
+operator= (const partner& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->name_ = x.name_;
+    this->id_ = x.id_;
+  }
+
+  return *this;
+}
+
+partner::
+~partner ()
+{
+}
+
+// cornerRoad
+//
+
+cornerRoad::
+cornerRoad ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  dz_ (this),
+  height_ (this)
+{
+}
+
+cornerRoad::
+cornerRoad (const cornerRoad& x,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  s_ (x.s_, f, this),
+  t_ (x.t_, f, this),
+  dz_ (x.dz_, f, this),
+  height_ (x.height_, f, this)
+{
+}
+
+cornerRoad::
+cornerRoad (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f,
+            ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  s_ (this),
+  t_ (this),
+  dz_ (this),
+  height_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void cornerRoad::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "s" && n.namespace_ ().empty ())
+    {
+      this->s_.set (s_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "t" && n.namespace_ ().empty ())
+    {
+      this->t_.set (t_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "dz" && n.namespace_ ().empty ())
+    {
+      this->dz_.set (dz_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+cornerRoad* cornerRoad::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class cornerRoad (*this, f, c);
+}
+
+cornerRoad& cornerRoad::
+operator= (const cornerRoad& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->s_ = x.s_;
+    this->t_ = x.t_;
+    this->dz_ = x.dz_;
+    this->height_ = x.height_;
+  }
+
+  return *this;
+}
+
+cornerRoad::
+~cornerRoad ()
+{
+}
+
+// cornerLocal
+//
+
+cornerLocal::
+cornerLocal ()
+: ::xml_schema::type (),
+  userData_ (this),
+  include_ (this),
+  u_ (this),
+  v_ (this),
+  z_ (this),
+  height_ (this)
+{
+}
+
+cornerLocal::
+cornerLocal (const cornerLocal& x,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (x, f, c),
+  userData_ (x.userData_, f, this),
+  include_ (x.include_, f, this),
+  u_ (x.u_, f, this),
+  v_ (x.v_, f, this),
+  z_ (x.z_, f, this),
+  height_ (x.height_, f, this)
+{
+}
+
+cornerLocal::
+cornerLocal (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f,
+             ::xml_schema::container* c)
+: ::xml_schema::type (e, f | ::xml_schema::flags::base, c),
+  userData_ (this),
+  include_ (this),
+  u_ (this),
+  v_ (this),
+  z_ (this),
+  height_ (this)
+{
+  if ((f & ::xml_schema::flags::base) == 0)
+  {
+    ::xsd::cxx::xml::dom::parser< char > p (e, true, false, true);
+    this->parse (p, f);
+  }
+}
+
+void cornerLocal::
+parse (::xsd::cxx::xml::dom::parser< char >& p,
+       ::xml_schema::flags f)
+{
+  for (; p.more_content (); p.next_content (false))
+  {
+    const ::xercesc::DOMElement& i (p.cur_element ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    // userData
+    //
+    if (n.name () == "userData" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< userData_type > r (
+        userData_traits::create (i, f, this));
+
+      this->userData_.push_back (::std::move (r));
+      continue;
+    }
+
+    // include
+    //
+    if (n.name () == "include" && n.namespace_ ().empty ())
+    {
+      ::std::unique_ptr< include_type > r (
+        include_traits::create (i, f, this));
+
+      this->include_.push_back (::std::move (r));
+      continue;
+    }
+
+    break;
+  }
+
+  while (p.more_attributes ())
+  {
+    const ::xercesc::DOMAttr& i (p.next_attribute ());
+    const ::xsd::cxx::xml::qualified_name< char > n (
+      ::xsd::cxx::xml::dom::name< char > (i));
+
+    if (n.name () == "u" && n.namespace_ ().empty ())
+    {
+      this->u_.set (u_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "v" && n.namespace_ ().empty ())
+    {
+      this->v_.set (v_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "z" && n.namespace_ ().empty ())
+    {
+      this->z_.set (z_traits::create (i, f, this));
+      continue;
+    }
+
+    if (n.name () == "height" && n.namespace_ ().empty ())
+    {
+      this->height_.set (height_traits::create (i, f, this));
+      continue;
+    }
+  }
+}
+
+cornerLocal* cornerLocal::
+_clone (::xml_schema::flags f,
+        ::xml_schema::container* c) const
+{
+  return new class cornerLocal (*this, f, c);
+}
+
+cornerLocal& cornerLocal::
+operator= (const cornerLocal& x)
+{
+  if (this != &x)
+  {
+    static_cast< ::xml_schema::type& > (*this) = x;
+    this->userData_ = x.userData_;
+    this->include_ = x.include_;
+    this->u_ = x.u_;
+    this->v_ = x.v_;
+    this->z_ = x.z_;
+    this->height_ = x.height_;
+  }
+
+  return *this;
+}
+
+cornerLocal::
+~cornerLocal ()
+{
+}
+
+#include <istream>
+#include <xsd/cxx/xml/sax/std-input-source.hxx>
+#include <xsd/cxx/tree/error-handler.hxx>
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& u,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xsd::cxx::tree::error_handler< char > h;
+
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      u, h, p, f));
+
+  h.throw_if_failed< ::xsd::cxx::tree::parsing< char > > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& u,
+            ::xml_schema::error_handler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      u, h, p, f));
+
+  if (!d.get ())
+    throw ::xsd::cxx::tree::parsing< char > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& u,
+            ::xercesc::DOMErrorHandler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      u, h, p, f));
+
+  if (!d.get ())
+    throw ::xsd::cxx::tree::parsing< char > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xsd::cxx::xml::sax::std_input_source isrc (is);
+  return ::OpenDRIVE_ (isrc, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xml_schema::error_handler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xsd::cxx::xml::sax::std_input_source isrc (is);
+  return ::OpenDRIVE_ (isrc, h, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xercesc::DOMErrorHandler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::sax::std_input_source isrc (is);
+  return ::OpenDRIVE_ (isrc, h, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& sid,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xsd::cxx::xml::sax::std_input_source isrc (is, sid);
+  return ::OpenDRIVE_ (isrc, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& sid,
+            ::xml_schema::error_handler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0,
+    (f & ::xml_schema::flags::keep_dom) == 0);
+
+  ::xsd::cxx::xml::sax::std_input_source isrc (is, sid);
+  return ::OpenDRIVE_ (isrc, h, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& sid,
+            ::xercesc::DOMErrorHandler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::xml::sax::std_input_source isrc (is, sid);
+  return ::OpenDRIVE_ (isrc, h, f, p);
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& i,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xsd::cxx::tree::error_handler< char > h;
+
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      i, h, p, f));
+
+  h.throw_if_failed< ::xsd::cxx::tree::parsing< char > > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& i,
+            ::xml_schema::error_handler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      i, h, p, f));
+
+  if (!d.get ())
+    throw ::xsd::cxx::tree::parsing< char > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& i,
+            ::xercesc::DOMErrorHandler& h,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::parse< char > (
+      i, h, p, f));
+
+  if (!d.get ())
+    throw ::xsd::cxx::tree::parsing< char > ();
+
+  return ::std::unique_ptr< ::OpenDRIVE > (
+    ::OpenDRIVE_ (
+      std::move (d), f | ::xml_schema::flags::own_dom, p));
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::xercesc::DOMDocument& doc,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties& p)
+{
+  if (f & ::xml_schema::flags::keep_dom)
+  {
+    ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+      static_cast< ::xercesc::DOMDocument* > (doc.cloneNode (true)));
+
+    return ::std::unique_ptr< ::OpenDRIVE > (
+      ::OpenDRIVE_ (
+        std::move (d), f | ::xml_schema::flags::own_dom, p));
+  }
+
+  const ::xercesc::DOMElement& e (*doc.getDocumentElement ());
+  const ::xsd::cxx::xml::qualified_name< char > n (
+    ::xsd::cxx::xml::dom::name< char > (e));
+
+  if (n.name () == "OpenDRIVE" &&
+      n.namespace_ () == "")
+  {
+    ::std::unique_ptr< ::OpenDRIVE > r (
+      ::xsd::cxx::tree::traits< ::OpenDRIVE, char >::create (
+        e, f, 0));
+    return r;
+  }
+
+  throw ::xsd::cxx::tree::unexpected_element < char > (
+    n.name (),
+    n.namespace_ (),
+    "OpenDRIVE",
+    "");
+}
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d,
+            ::xml_schema::flags f,
+            const ::xml_schema::properties&)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > c (
+    ((f & ::xml_schema::flags::keep_dom) &&
+     !(f & ::xml_schema::flags::own_dom))
+    ? static_cast< ::xercesc::DOMDocument* > (d->cloneNode (true))
+    : 0);
+
+  ::xercesc::DOMDocument& doc (c.get () ? *c : *d);
+  const ::xercesc::DOMElement& e (*doc.getDocumentElement ());
+
+  const ::xsd::cxx::xml::qualified_name< char > n (
+    ::xsd::cxx::xml::dom::name< char > (e));
+
+  if (f & ::xml_schema::flags::keep_dom)
+    doc.setUserData (::xml_schema::dom::tree_node_key,
+                     (c.get () ? &c : &d),
+                     0);
+
+  if (n.name () == "OpenDRIVE" &&
+      n.namespace_ () == "")
+  {
+    ::std::unique_ptr< ::OpenDRIVE > r (
+      ::xsd::cxx::tree::traits< ::OpenDRIVE, char >::create (
+        e, f, 0));
+    return r;
+  }
+
+  throw ::xsd::cxx::tree::unexpected_element < char > (
+    n.name (),
+    n.namespace_ (),
+    "OpenDRIVE",
+    "");
+}
+
+#include <ostream>
+#include <xsd/cxx/tree/error-handler.hxx>
+#include <xsd/cxx/xml/dom/serialization-source.hxx>
+
+void
+OpenDRIVE_ (::std::ostream& o,
+            const ::OpenDRIVE& s,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0);
+
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+
+  ::xsd::cxx::tree::error_handler< char > h;
+
+  ::xsd::cxx::xml::dom::ostream_format_target t (o);
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    h.throw_if_failed< ::xsd::cxx::tree::serialization< char > > ();
+  }
+}
+
+void
+OpenDRIVE_ (::std::ostream& o,
+            const ::OpenDRIVE& s,
+            ::xml_schema::error_handler& h,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xsd::cxx::xml::auto_initializer i (
+    (f & ::xml_schema::flags::dont_initialize) == 0);
+
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+  ::xsd::cxx::xml::dom::ostream_format_target t (o);
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    throw ::xsd::cxx::tree::serialization< char > ();
+  }
+}
+
+void
+OpenDRIVE_ (::std::ostream& o,
+            const ::OpenDRIVE& s,
+            ::xercesc::DOMErrorHandler& h,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+  ::xsd::cxx::xml::dom::ostream_format_target t (o);
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    throw ::xsd::cxx::tree::serialization< char > ();
+  }
+}
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& t,
+            const ::OpenDRIVE& s,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+
+  ::xsd::cxx::tree::error_handler< char > h;
+
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    h.throw_if_failed< ::xsd::cxx::tree::serialization< char > > ();
+  }
+}
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& t,
+            const ::OpenDRIVE& s,
+            ::xml_schema::error_handler& h,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    throw ::xsd::cxx::tree::serialization< char > ();
+  }
+}
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& t,
+            const ::OpenDRIVE& s,
+            ::xercesc::DOMErrorHandler& h,
+            const ::xml_schema::namespace_infomap& m,
+            const ::std::string& e,
+            ::xml_schema::flags f)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::OpenDRIVE_ (s, m, f));
+  if (!::xsd::cxx::xml::dom::serialize (t, *d, e, h, f))
+  {
+    throw ::xsd::cxx::tree::serialization< char > ();
+  }
+}
+
+void
+OpenDRIVE_ (::xercesc::DOMDocument& d,
+            const ::OpenDRIVE& s,
+            ::xml_schema::flags)
+{
+  ::xercesc::DOMElement& e (*d.getDocumentElement ());
+  const ::xsd::cxx::xml::qualified_name< char > n (
+    ::xsd::cxx::xml::dom::name< char > (e));
+
+  if (n.name () == "OpenDRIVE" &&
+      n.namespace_ () == "")
+  {
+    e << s;
+  }
+  else
+  {
+    throw ::xsd::cxx::tree::unexpected_element < char > (
+      n.name (),
+      n.namespace_ (),
+      "OpenDRIVE",
+      "");
+  }
+}
+
+::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument >
+OpenDRIVE_ (const ::OpenDRIVE& s,
+            const ::xml_schema::namespace_infomap& m,
+            ::xml_schema::flags f)
+{
+  ::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d (
+    ::xsd::cxx::xml::dom::serialize< char > (
+      "OpenDRIVE",
+      "",
+      m, f));
+
+  ::OpenDRIVE_ (*d, s, f);
+  return d;
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const elementType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const elementType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const elementType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const max& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const max& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const max& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const contactPoint& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const contactPoint& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const contactPoint& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const side& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const side& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const side& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const direction& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const direction& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const direction& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const roadType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const roadType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const roadType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const unit& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const unit& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const unit& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const pRange& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const pRange& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const pRange& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const crossfallSide& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const crossfallSide& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const crossfallSide& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const singleSide& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const singleSide& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const singleSide& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const laneType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const laneType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const roadmarkType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const roadmarkType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const roadmarkType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const weight& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const weight& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const weight& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const color& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const color& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const color& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const restriction& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const restriction& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const restriction& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneChange& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const laneChange& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const laneChange& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const rule& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const rule& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const rule& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const orientation& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const orientation& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const orientation& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const tunnelType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const tunnelType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const tunnelType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const bridgeType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const bridgeType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const bridgeType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const parkingSpace_access& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const parkingSpace_access& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const parkingSpace_access& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const parkingSpacemarkingSide& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const parkingSpacemarkingSide& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const parkingSpacemarkingSide& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const dynamic& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const dynamic& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const dynamic& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const surfaceOrientation& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const surfaceOrientation& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const surfaceOrientation& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const mode& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const mode& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const mode& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const purpose& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const purpose& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const purpose& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const position& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const position& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const position& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const dir& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const dir& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const dir& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const junctionGroupType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const junctionGroupType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const junctionGroupType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const stationType& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const stationType& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const stationType& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const userData& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // code
+  //
+  if (i.code ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "code",
+        e));
+
+    a << *i.code ();
+  }
+
+  // value
+  //
+  if (i.value ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "value",
+        e));
+
+    a << *i.value ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const include& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // file
+  //
+  if (i.file ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "file",
+        e));
+
+    a << *i.file ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneValidity& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (laneValidity::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (laneValidity::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // fromLane
+  //
+  if (i.fromLane ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "fromLane",
+        e));
+
+    a << *i.fromLane ();
+  }
+
+  // toLane
+  //
+  if (i.toLane ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "toLane",
+        e));
+
+    a << *i.toLane ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const parkingSpace& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // marking
+  //
+  for (parkingSpace::marking_const_iterator
+       b (i.marking ().begin ()), n (i.marking ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "marking",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (parkingSpace::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (parkingSpace::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // access
+  //
+  if (i.parkingSpace_access ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "access",
+        e));
+
+    a << *i.parkingSpace_access ();
+  }
+
+  // restrictions
+  //
+  if (i.restrictions ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "restrictions",
+        e));
+
+    a << *i.restrictions ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const lane& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // link
+  //
+  if (i.lane_link ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "link",
+        e));
+
+    s << *i.lane_link ();
+  }
+
+  // width
+  //
+  for (lane::width_const_iterator
+       b (i.width ().begin ()), n (i.width ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "width",
+        e));
+
+    s << *b;
+  }
+
+  // border
+  //
+  for (lane::border_const_iterator
+       b (i.border ().begin ()), n (i.border ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "border",
+        e));
+
+    s << *b;
+  }
+
+  // roadMark
+  //
+  for (lane::roadMark_const_iterator
+       b (i.roadMark ().begin ()), n (i.roadMark ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "roadMark",
+        e));
+
+    s << *b;
+  }
+
+  // material
+  //
+  for (lane::material_const_iterator
+       b (i.material ().begin ()), n (i.material ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "material",
+        e));
+
+    s << *b;
+  }
+
+  // visibility
+  //
+  for (lane::visibility_const_iterator
+       b (i.visibility ().begin ()), n (i.visibility ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "visibility",
+        e));
+
+    s << *b;
+  }
+
+  // speed
+  //
+  for (lane::speed_const_iterator
+       b (i.speed ().begin ()), n (i.speed ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "speed",
+        e));
+
+    s << *b;
+  }
+
+  // access
+  //
+  for (lane::access_const_iterator
+       b (i.parkingSpace_access ().begin ()), n (i.parkingSpace_access ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "access",
+        e));
+
+    s << *b;
+  }
+
+  // height
+  //
+  for (lane::height_const_iterator
+       b (i.height ().begin ()), n (i.height ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "height",
+        e));
+
+    s << *b;
+  }
+
+  // rule
+  //
+  for (lane::rule_const_iterator
+       b (i.rule ().begin ()), n (i.rule ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "rule",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (lane::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (lane::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // level
+  //
+  if (i.level ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "level",
+        e));
+
+    a << *i.level ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const centerLane& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // link
+  //
+  if (i.lane_link ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "link",
+        e));
+
+    s << *i.lane_link ();
+  }
+
+  // roadMark
+  //
+  for (centerLane::roadMark_const_iterator
+       b (i.roadMark ().begin ()), n (i.roadMark ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "roadMark",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (centerLane::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (centerLane::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // level
+  //
+  if (i.level ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "level",
+        e));
+
+    a << *i.level ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const OpenDRIVE& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // header
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "header",
+        e));
+
+    s << i.header ();
+  }
+
+  // road
+  //
+  for (OpenDRIVE::road_const_iterator
+       b (i.road ().begin ()), n (i.road ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "road",
+        e));
+
+    s << *b;
+  }
+
+  // controller
+  //
+  for (OpenDRIVE::controller_const_iterator
+       b (i.controller ().begin ()), n (i.controller ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "controller",
+        e));
+
+    s << *b;
+  }
+
+  // junction
+  //
+  for (OpenDRIVE::junction_const_iterator
+       b (i.junction ().begin ()), n (i.junction ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "junction",
+        e));
+
+    s << *b;
+  }
+
+  // junctionGroup
+  //
+  for (OpenDRIVE::junctionGroup_const_iterator
+       b (i.junctionGroup ().begin ()), n (i.junctionGroup ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "junctionGroup",
+        e));
+
+    s << *b;
+  }
+
+  // station
+  //
+  for (OpenDRIVE::station_const_iterator
+       b (i.station ().begin ()), n (i.station ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "station",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const max_member& i)
+{
+  e << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const max_member& i)
+{
+  a << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const max_member& i)
+{
+  l << static_cast< const ::xml_schema::string& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const max_member1& i)
+{
+  e << static_cast< const ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type >& > (i);
+}
+
+void
+operator<< (::xercesc::DOMAttr& a, const max_member1& i)
+{
+  a << static_cast< const ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type >& > (i);
+}
+
+void
+operator<< (::xml_schema::list_stream& l,
+            const max_member1& i)
+{
+  l << static_cast< const ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type >& > (i);
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const marking& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // side
+  //
+  if (i.side ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "side",
+        e));
+
+    a << *i.side ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+
+  // color
+  //
+  if (i.color ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "color",
+        e));
+
+    a << *i.color ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const lane_link& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // predecessor
+  //
+  if (i.predecessor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "predecessor",
+        e));
+
+    s << *i.predecessor ();
+  }
+
+  // successor
+  //
+  if (i.successor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "successor",
+        e));
+
+    s << *i.successor ();
+  }
+
+  // userData
+  //
+  for (lane_link::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (lane_link::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const width& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (width::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (width::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const border& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (border::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (border::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const roadMark& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "type",
+        e));
+
+    s << *i.type ();
+  }
+
+  // userData
+  //
+  for (roadMark::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (roadMark::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // type
+  //
+  if (i.type1 ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type1 ();
+  }
+
+  // weight
+  //
+  if (i.weight ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "weight",
+        e));
+
+    a << *i.weight ();
+  }
+
+  // color
+  //
+  if (i.color ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "color",
+        e));
+
+    a << *i.color ();
+  }
+
+  // material
+  //
+  if (i.material ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "material",
+        e));
+
+    a << *i.material ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+
+  // laneChange
+  //
+  if (i.laneChange ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "laneChange",
+        e));
+
+    a << *i.laneChange ();
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const material& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (material::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (material::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // surface
+  //
+  if (i.surface ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "surface",
+        e));
+
+    a << *i.surface ();
+  }
+
+  // friction
+  //
+  if (i.friction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "friction",
+        e));
+
+    a << ::xml_schema::as_double(*i.friction ());
+  }
+
+  // roughness
+  //
+  if (i.roughness ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "roughness",
+        e));
+
+    a << ::xml_schema::as_double(*i.roughness ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const visibility& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (visibility::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (visibility::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // forward
+  //
+  if (i.forward ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "forward",
+        e));
+
+    a << ::xml_schema::as_double(*i.forward ());
+  }
+
+  // back
+  //
+  if (i.back ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "back",
+        e));
+
+    a << ::xml_schema::as_double(*i.back ());
+  }
+
+  // left
+  //
+  if (i.left ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "left",
+        e));
+
+    a << ::xml_schema::as_double(*i.left ());
+  }
+
+  // right
+  //
+  if (i.right ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "right",
+        e));
+
+    a << ::xml_schema::as_double(*i.right ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const speed& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (speed::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (speed::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // max
+  //
+  if (i.max ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "max",
+        e));
+
+    a << ::xml_schema::as_double(*i.max ());
+  }
+
+  // unit
+  //
+  if (i.unit ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "unit",
+        e));
+
+    a << *i.unit ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const access1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (access1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (access1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // restriction
+  //
+  if (i.restriction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "restriction",
+        e));
+
+    a << *i.restriction ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const height& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (height::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (height::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // inner
+  //
+  if (i.inner ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "inner",
+        e));
+
+    a << ::xml_schema::as_double(*i.inner ());
+  }
+
+  // outer
+  //
+  if (i.outer ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "outer",
+        e));
+
+    a << ::xml_schema::as_double(*i.outer ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const rule1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (rule1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (rule1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // value
+  //
+  if (i.value ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "value",
+        e));
+
+    a << *i.value ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const link1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // predecessor
+  //
+  if (i.predecessor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "predecessor",
+        e));
+
+    s << *i.predecessor ();
+  }
+
+  // successor
+  //
+  if (i.successor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "successor",
+        e));
+
+    s << *i.successor ();
+  }
+
+  // userData
+  //
+  for (link1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (link1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const roadMark1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "type",
+        e));
+
+    s << *i.type ();
+  }
+
+  // userData
+  //
+  for (roadMark1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (roadMark1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // type
+  //
+  if (i.type1 ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type1 ();
+  }
+
+  // weight
+  //
+  if (i.weight ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "weight",
+        e));
+
+    a << *i.weight ();
+  }
+
+  // color
+  //
+  if (i.color ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "color",
+        e));
+
+    a << *i.color ();
+  }
+
+  // material
+  //
+  if (i.material ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "material",
+        e));
+
+    a << *i.material ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+
+  // laneChange
+  //
+  if (i.laneChange ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "laneChange",
+        e));
+
+    a << *i.laneChange ();
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const header& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // geoReference
+  //
+  if (i.geoReference ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "geoReference",
+        e));
+
+    s << *i.geoReference ();
+  }
+
+  // userData
+  //
+  for (header::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (header::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // revMajor
+  //
+  if (i.revMajor ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "revMajor",
+        e));
+
+    a << *i.revMajor ();
+  }
+
+  // revMinor
+  //
+  if (i.revMinor ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "revMinor",
+        e));
+
+    a << *i.revMinor ();
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // version
+  //
+  if (i.version ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "version",
+        e));
+
+    a << *i.version ();
+  }
+
+  // date
+  //
+  if (i.date ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "date",
+        e));
+
+    a << *i.date ();
+  }
+
+  // north
+  //
+  if (i.north ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "north",
+        e));
+
+    a << ::xml_schema::as_double(*i.north ());
+  }
+
+  // south
+  //
+  if (i.south ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "south",
+        e));
+
+    a << ::xml_schema::as_double(*i.south ());
+  }
+
+  // east
+  //
+  if (i.east ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "east",
+        e));
+
+    a << ::xml_schema::as_double(*i.east ());
+  }
+
+  // west
+  //
+  if (i.west ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "west",
+        e));
+
+    a << ::xml_schema::as_double(*i.west ());
+  }
+
+  // vendor
+  //
+  if (i.vendor ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "vendor",
+        e));
+
+    a << *i.vendor ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const road& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // link
+  //
+  if (i.lane_link ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "link",
+        e));
+
+    s << *i.lane_link ();
+  }
+
+  // type
+  //
+  for (road::type_const_iterator
+       b (i.type ().begin ()), n (i.type ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "type",
+        e));
+
+    s << *b;
+  }
+
+  // planView
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "planView",
+        e));
+
+    s << i.planView ();
+  }
+
+  // elevationProfile
+  //
+  if (i.elevationProfile ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "elevationProfile",
+        e));
+
+    s << *i.elevationProfile ();
+  }
+
+  // lateralProfile
+  //
+  if (i.lateralProfile ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "lateralProfile",
+        e));
+
+    s << *i.lateralProfile ();
+  }
+
+  // lanes
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "lanes",
+        e));
+
+    s << i.lanes ();
+  }
+
+  // objects
+  //
+  if (i.objects ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "objects",
+        e));
+
+    s << *i.objects ();
+  }
+
+  // signals
+  //
+  if (i.signals ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "signals",
+        e));
+
+    s << *i.signals ();
+  }
+
+  // surface
+  //
+  if (i.surface ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "surface",
+        e));
+
+    s << *i.surface ();
+  }
+
+  // railroad
+  //
+  if (i.railroad ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "railroad",
+        e));
+
+    s << *i.railroad ();
+  }
+
+  // userData
+  //
+  for (road::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (road::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // junction
+  //
+  if (i.junction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "junction",
+        e));
+
+    a << *i.junction ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const controller& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // control
+  //
+  for (controller::control_const_iterator
+       b (i.control ().begin ()), n (i.control ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "control",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (controller::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (controller::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // sequence
+  //
+  if (i.sequence ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sequence",
+        e));
+
+    a << *i.sequence ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const junction& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // connection
+  //
+  for (junction::connection_const_iterator
+       b (i.connection ().begin ()), n (i.connection ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "connection",
+        e));
+
+    s << *b;
+  }
+
+  // priority
+  //
+  for (junction::priority_const_iterator
+       b (i.priority ().begin ()), n (i.priority ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "priority",
+        e));
+
+    s << *b;
+  }
+
+  // controller
+  //
+  for (junction::controller_const_iterator
+       b (i.controller ().begin ()), n (i.controller ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "controller",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (junction::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (junction::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const junctionGroup& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // junctionReference
+  //
+  for (junctionGroup::junctionReference_const_iterator
+       b (i.junctionReference ().begin ()), n (i.junctionReference ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "junctionReference",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (junctionGroup::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (junctionGroup::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const station& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // platform
+  //
+  for (station::platform_const_iterator
+       b (i.platform ().begin ()), n (i.platform ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "platform",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (station::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (station::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const predecessor& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const successor& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const type& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // line
+  //
+  for (type::line_const_iterator
+       b (i.line ().begin ()), n (i.line ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "line",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const type1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // line
+  //
+  for (type1::line_const_iterator
+       b (i.line ().begin ()), n (i.line ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "line",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const link2& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // predecessor
+  //
+  if (i.predecessor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "predecessor",
+        e));
+
+    s << *i.predecessor ();
+  }
+
+  // successor
+  //
+  if (i.successor ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "successor",
+        e));
+
+    s << *i.successor ();
+  }
+
+  // neighbor
+  //
+  for (link2::neighbor_const_iterator
+       b (i.neighbor ().begin ()), n (i.neighbor ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "neighbor",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (link2::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (link2::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const type2& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // speed
+  //
+  if (i.speed ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "speed",
+        e));
+
+    s << *i.speed ();
+  }
+
+  // userData
+  //
+  for (type2::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (type2::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const planView& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // geometry
+  //
+  for (planView::geometry_const_iterator
+       b (i.geometry ().begin ()), n (i.geometry ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "geometry",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const elevationProfile& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // elevation
+  //
+  for (elevationProfile::elevation_const_iterator
+       b (i.elevation ().begin ()), n (i.elevation ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "elevation",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (elevationProfile::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (elevationProfile::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const lateralProfile& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // superelevation
+  //
+  for (lateralProfile::superelevation_const_iterator
+       b (i.superelevation ().begin ()), n (i.superelevation ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "superelevation",
+        e));
+
+    s << *b;
+  }
+
+  // crossfall
+  //
+  for (lateralProfile::crossfall_const_iterator
+       b (i.crossfall ().begin ()), n (i.crossfall ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "crossfall",
+        e));
+
+    s << *b;
+  }
+
+  // shape
+  //
+  for (lateralProfile::shape_const_iterator
+       b (i.shape ().begin ()), n (i.shape ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "shape",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (lateralProfile::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (lateralProfile::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const lanes& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // laneOffset
+  //
+  for (lanes::laneOffset_const_iterator
+       b (i.laneOffset ().begin ()), n (i.laneOffset ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "laneOffset",
+        e));
+
+    s << *b;
+  }
+
+  // laneSection
+  //
+  for (lanes::laneSection_const_iterator
+       b (i.laneSection ().begin ()), n (i.laneSection ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "laneSection",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const objects& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // object
+  //
+  for (objects::object_const_iterator
+       b (i.object ().begin ()), n (i.object ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "object",
+        e));
+
+    s << *b;
+  }
+
+  // objectReference
+  //
+  for (objects::objectReference_const_iterator
+       b (i.objectReference ().begin ()), n (i.objectReference ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "objectReference",
+        e));
+
+    s << *b;
+  }
+
+  // tunnel
+  //
+  for (objects::tunnel_const_iterator
+       b (i.tunnel ().begin ()), n (i.tunnel ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "tunnel",
+        e));
+
+    s << *b;
+  }
+
+  // bridge
+  //
+  for (objects::bridge_const_iterator
+       b (i.bridge ().begin ()), n (i.bridge ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "bridge",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (objects::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (objects::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const signals& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // signal
+  //
+  for (signals::signal_const_iterator
+       b (i.signal ().begin ()), n (i.signal ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "signal",
+        e));
+
+    s << *b;
+  }
+
+  // signalReference
+  //
+  for (signals::signalReference_const_iterator
+       b (i.signalReference ().begin ()), n (i.signalReference ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "signalReference",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (signals::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (signals::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const surface& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // CRG
+  //
+  for (surface::CRG_const_iterator
+       b (i.CRG ().begin ()), n (i.CRG ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "CRG",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (surface::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (surface::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const railroad& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // switch
+  //
+  for (railroad::switch_const_iterator
+       b (i.switch_ ().begin ()), n (i.switch_ ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "switch",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (railroad::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (railroad::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const control& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (control::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (control::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // signalId
+  //
+  if (i.signalId ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "signalId",
+        e));
+
+    a << *i.signalId ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const connection& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // laneLink
+  //
+  for (connection::laneLink_const_iterator
+       b (i.laneLink ().begin ()), n (i.laneLink ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "laneLink",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (connection::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (connection::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // incomingRoad
+  //
+  if (i.incomingRoad ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "incomingRoad",
+        e));
+
+    a << *i.incomingRoad ();
+  }
+
+  // connectingRoad
+  //
+  if (i.connectingRoad ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "connectingRoad",
+        e));
+
+    a << *i.connectingRoad ();
+  }
+
+  // contactPoint
+  //
+  if (i.contactPoint ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "contactPoint",
+        e));
+
+    a << *i.contactPoint ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const priority& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (priority::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (priority::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // high
+  //
+  if (i.high ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "high",
+        e));
+
+    a << *i.high ();
+  }
+
+  // low
+  //
+  if (i.low ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "low",
+        e));
+
+    a << *i.low ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const controller1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (controller1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (controller1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // sequence
+  //
+  if (i.sequence ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sequence",
+        e));
+
+    a << *i.sequence ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const junctionReference& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // junction
+  //
+  if (i.junction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "junction",
+        e));
+
+    a << *i.junction ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const platform& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // segment
+  //
+  for (platform::segment_const_iterator
+       b (i.segment ().begin ()), n (i.segment ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "segment",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const line& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // space
+  //
+  if (i.space ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "space",
+        e));
+
+    a << ::xml_schema::as_double(*i.space ());
+  }
+
+  // tOffset
+  //
+  if (i.tOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "tOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.tOffset ());
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // rule
+  //
+  if (i.rule ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "rule",
+        e));
+
+    a << *i.rule ();
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const predecessor1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // elementType
+  //
+  if (i.elementType ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "elementType",
+        e));
+
+    a << *i.elementType ();
+  }
+
+  // elementId
+  //
+  if (i.elementId ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "elementId",
+        e));
+
+    a << *i.elementId ();
+  }
+
+  // contactPoint
+  //
+  if (i.contactPoint ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "contactPoint",
+        e));
+
+    a << *i.contactPoint ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const successor1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // elementType
+  //
+  if (i.elementType ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "elementType",
+        e));
+
+    a << *i.elementType ();
+  }
+
+  // elementId
+  //
+  if (i.elementId ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "elementId",
+        e));
+
+    a << *i.elementId ();
+  }
+
+  // contactPoint
+  //
+  if (i.contactPoint ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "contactPoint",
+        e));
+
+    a << *i.contactPoint ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const neighbor& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // side
+  //
+  if (i.side ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "side",
+        e));
+
+    a << *i.side ();
+  }
+
+  // elementId
+  //
+  if (i.elementId ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "elementId",
+        e));
+
+    a << *i.elementId ();
+  }
+
+  // direction
+  //
+  if (i.direction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "direction",
+        e));
+
+    a << *i.direction ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const speed1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // max
+  //
+  if (i.max ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "max",
+        e));
+
+    a << *i.max ();
+  }
+
+  // unit
+  //
+  if (i.unit ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "unit",
+        e));
+
+    a << *i.unit ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const geometry& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // line
+  //
+  if (i.line ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "line",
+        e));
+
+    s << *i.line ();
+  }
+
+  // spiral
+  //
+  if (i.spiral ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "spiral",
+        e));
+
+    s << *i.spiral ();
+  }
+
+  // arc
+  //
+  if (i.arc ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "arc",
+        e));
+
+    s << *i.arc ();
+  }
+
+  // poly3
+  //
+  if (i.poly3 ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "poly3",
+        e));
+
+    s << *i.poly3 ();
+  }
+
+  // paramPoly3
+  //
+  if (i.paramPoly3 ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "paramPoly3",
+        e));
+
+    s << *i.paramPoly3 ();
+  }
+
+  // userData
+  //
+  for (geometry::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (geometry::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // x
+  //
+  if (i.x ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "x",
+        e));
+
+    a << ::xml_schema::as_double(*i.x ());
+  }
+
+  // y
+  //
+  if (i.y ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "y",
+        e));
+
+    a << ::xml_schema::as_double(*i.y ());
+  }
+
+  // hdg
+  //
+  if (i.hdg ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "hdg",
+        e));
+
+    a << ::xml_schema::as_double(*i.hdg ());
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const elevation& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (elevation::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (elevation::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const superelevation& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (superelevation::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (superelevation::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const crossfall& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (crossfall::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (crossfall::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // side
+  //
+  if (i.side ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "side",
+        e));
+
+    a << *i.side ();
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const shape& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (shape::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (shape::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneOffset& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (laneOffset::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (laneOffset::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneSection& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // left
+  //
+  if (i.left ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "left",
+        e));
+
+    s << *i.left ();
+  }
+
+  // center
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "center",
+        e));
+
+    s << i.center ();
+  }
+
+  // right
+  //
+  if (i.right ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "right",
+        e));
+
+    s << *i.right ();
+  }
+
+  // userData
+  //
+  for (laneSection::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (laneSection::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // singleSide
+  //
+  if (i.singleSide ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "singleSide",
+        e));
+
+    a << *i.singleSide ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const object& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // repeat
+  //
+  for (object::repeat_const_iterator
+       b (i.repeat ().begin ()), n (i.repeat ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "repeat",
+        e));
+
+    s << *b;
+  }
+
+  // outline
+  //
+  if (i.outline ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "outline",
+        e));
+
+    s << *i.outline ();
+  }
+
+  // material
+  //
+  if (i.material ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "material",
+        e));
+
+    s << *i.material ();
+  }
+
+  // validity
+  //
+  for (object::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // parkingSpace
+  //
+  if (i.parkingSpace ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "parkingSpace",
+        e));
+
+    s << *i.parkingSpace ();
+  }
+
+  // userData
+  //
+  for (object::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (object::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // zOffset
+  //
+  if (i.zOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffset ());
+  }
+
+  // validLength
+  //
+  if (i.validLength ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "validLength",
+        e));
+
+    a << ::xml_schema::as_double(*i.validLength ());
+  }
+
+  // orientation
+  //
+  if (i.orientation ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "orientation",
+        e));
+
+    a << *i.orientation ();
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+
+  // radius
+  //
+  if (i.radius ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "radius",
+        e));
+
+    a << ::xml_schema::as_double(*i.radius ());
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+
+  // hdg
+  //
+  if (i.hdg ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "hdg",
+        e));
+
+    a << ::xml_schema::as_double(*i.hdg ());
+  }
+
+  // pitch
+  //
+  if (i.pitch ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "pitch",
+        e));
+
+    a << ::xml_schema::as_double(*i.pitch ());
+  }
+
+  // roll
+  //
+  if (i.roll ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "roll",
+        e));
+
+    a << ::xml_schema::as_double(*i.roll ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const objectReference& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // validity
+  //
+  for (objectReference::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (objectReference::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (objectReference::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // zOffset
+  //
+  if (i.zOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffset ());
+  }
+
+  // validLength
+  //
+  if (i.validLength ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "validLength",
+        e));
+
+    a << ::xml_schema::as_double(*i.validLength ());
+  }
+
+  // orientation
+  //
+  if (i.orientation ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "orientation",
+        e));
+
+    a << *i.orientation ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const tunnel& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // validity
+  //
+  for (tunnel::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (tunnel::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (tunnel::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // lighting
+  //
+  if (i.lighting ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "lighting",
+        e));
+
+    a << ::xml_schema::as_double(*i.lighting ());
+  }
+
+  // daylight
+  //
+  if (i.daylight ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "daylight",
+        e));
+
+    a << ::xml_schema::as_double(*i.daylight ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const bridge& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // validity
+  //
+  for (bridge::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (bridge::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (bridge::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const signal& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // validity
+  //
+  for (signal::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // dependency
+  //
+  for (signal::dependency_const_iterator
+       b (i.dependency ().begin ()), n (i.dependency ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "dependency",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (signal::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (signal::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // dynamic
+  //
+  if (i.dynamic ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dynamic",
+        e));
+
+    a << *i.dynamic ();
+  }
+
+  // orientation
+  //
+  if (i.orientation ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "orientation",
+        e));
+
+    a << *i.orientation ();
+  }
+
+  // zOffset
+  //
+  if (i.zOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffset ());
+  }
+
+  // country
+  //
+  if (i.country ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "country",
+        e));
+
+    a << *i.country ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+
+  // subtype
+  //
+  if (i.subtype ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "subtype",
+        e));
+
+    a << *i.subtype ();
+  }
+
+  // value
+  //
+  if (i.value ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "value",
+        e));
+
+    a << ::xml_schema::as_double(*i.value ());
+  }
+
+  // unit
+  //
+  if (i.unit ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "unit",
+        e));
+
+    a << *i.unit ();
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+
+  // width
+  //
+  if (i.width ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "width",
+        e));
+
+    a << ::xml_schema::as_double(*i.width ());
+  }
+
+  // text
+  //
+  if (i.text ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "text",
+        e));
+
+    a << *i.text ();
+  }
+
+  // hOffset
+  //
+  if (i.hOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "hOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.hOffset ());
+  }
+
+  // pitch
+  //
+  if (i.pitch ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "pitch",
+        e));
+
+    a << ::xml_schema::as_double(*i.pitch ());
+  }
+
+  // roll
+  //
+  if (i.roll ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "roll",
+        e));
+
+    a << ::xml_schema::as_double(*i.roll ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const signalReference& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // validity
+  //
+  for (signalReference::validity_const_iterator
+       b (i.validity ().begin ()), n (i.validity ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "validity",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (signalReference::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (signalReference::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // orientation
+  //
+  if (i.orientation ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "orientation",
+        e));
+
+    a << *i.orientation ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const CRG& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (CRG::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (CRG::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // file
+  //
+  if (i.file ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "file",
+        e));
+
+    a << *i.file ();
+  }
+
+  // sStart
+  //
+  if (i.sStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.sStart ());
+  }
+
+  // sEnd
+  //
+  if (i.sEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.sEnd ());
+  }
+
+  // orientation
+  //
+  if (i.orientation ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "orientation",
+        e));
+
+    a << *i.orientation ();
+  }
+
+  // mode
+  //
+  if (i.mode ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "mode",
+        e));
+
+    a << *i.mode ();
+  }
+
+  // purpose
+  //
+  if (i.purpose ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "purpose",
+        e));
+
+    a << *i.purpose ();
+  }
+
+  // sOffset
+  //
+  if (i.sOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.sOffset ());
+  }
+
+  // tOffset
+  //
+  if (i.tOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "tOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.tOffset ());
+  }
+
+  // zOffset
+  //
+  if (i.zOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffset ());
+  }
+
+  // zScale
+  //
+  if (i.zScale ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zScale",
+        e));
+
+    a << ::xml_schema::as_double(*i.zScale ());
+  }
+
+  // hOffset
+  //
+  if (i.hOffset ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "hOffset",
+        e));
+
+    a << ::xml_schema::as_double(*i.hOffset ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const switch_& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // mainTrack
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "mainTrack",
+        e));
+
+    s << i.mainTrack ();
+  }
+
+  // sideTrack
+  //
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "sideTrack",
+        e));
+
+    s << i.sideTrack ();
+  }
+
+  // partner
+  //
+  if (i.partner ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "partner",
+        e));
+
+    s << *i.partner ();
+  }
+
+  // userData
+  //
+  for (switch_::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (switch_::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // position
+  //
+  if (i.position ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "position",
+        e));
+
+    a << *i.position ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const laneLink& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (laneLink::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (laneLink::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // from
+  //
+  if (i.from ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "from",
+        e));
+
+    a << *i.from ();
+  }
+
+  // to
+  //
+  if (i.to ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "to",
+        e));
+
+    a << *i.to ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const segment& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (segment::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (segment::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // roadId
+  //
+  if (i.roadId ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "roadId",
+        e));
+
+    a << *i.roadId ();
+  }
+
+  // sStart
+  //
+  if (i.sStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.sStart ());
+  }
+
+  // sEnd
+  //
+  if (i.sEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "sEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.sEnd ());
+  }
+
+  // side
+  //
+  if (i.side ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "side",
+        e));
+
+    a << *i.side ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const line1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (line1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (line1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const spiral& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (spiral::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (spiral::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // curvStart
+  //
+  if (i.curvStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "curvStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.curvStart ());
+  }
+
+  // curvEnd
+  //
+  if (i.curvEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "curvEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.curvEnd ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const arc& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (arc::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (arc::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // curvature
+  //
+  if (i.curvature ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "curvature",
+        e));
+
+    a << ::xml_schema::as_double(*i.curvature ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const poly3& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (poly3::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (poly3::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // a
+  //
+  if (i.a ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "a",
+        e));
+
+    a << ::xml_schema::as_double(*i.a ());
+  }
+
+  // b
+  //
+  if (i.b ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "b",
+        e));
+
+    a << ::xml_schema::as_double(*i.b ());
+  }
+
+  // c
+  //
+  if (i.c ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "c",
+        e));
+
+    a << ::xml_schema::as_double(*i.c ());
+  }
+
+  // d
+  //
+  if (i.d ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "d",
+        e));
+
+    a << ::xml_schema::as_double(*i.d ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const paramPoly3& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (paramPoly3::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (paramPoly3::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // aU
+  //
+  if (i.aU ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "aU",
+        e));
+
+    a << ::xml_schema::as_double(*i.aU ());
+  }
+
+  // bU
+  //
+  if (i.bU ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "bU",
+        e));
+
+    a << ::xml_schema::as_double(*i.bU ());
+  }
+
+  // cU
+  //
+  if (i.cU ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "cU",
+        e));
+
+    a << ::xml_schema::as_double(*i.cU ());
+  }
+
+  // dU
+  //
+  if (i.dU ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dU",
+        e));
+
+    a << ::xml_schema::as_double(*i.dU ());
+  }
+
+  // aV
+  //
+  if (i.aV ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "aV",
+        e));
+
+    a << ::xml_schema::as_double(*i.aV ());
+  }
+
+  // bV
+  //
+  if (i.bV ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "bV",
+        e));
+
+    a << ::xml_schema::as_double(*i.bV ());
+  }
+
+  // cV
+  //
+  if (i.cV ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "cV",
+        e));
+
+    a << ::xml_schema::as_double(*i.cV ());
+  }
+
+  // dV
+  //
+  if (i.dV ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dV",
+        e));
+
+    a << ::xml_schema::as_double(*i.dV ());
+  }
+
+  // pRange
+  //
+  if (i.pRange ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "pRange",
+        e));
+
+    a << *i.pRange ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const left& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // lane
+  //
+  for (left::lane_const_iterator
+       b (i.lane ().begin ()), n (i.lane ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "lane",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (left::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (left::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const center& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // lane
+  //
+  if (i.lane ())
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "lane",
+        e));
+
+    s << *i.lane ();
+  }
+
+  // userData
+  //
+  for (center::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (center::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const right& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // lane
+  //
+  for (right::lane_const_iterator
+       b (i.lane ().begin ()), n (i.lane ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "lane",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (right::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (right::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const repeat& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (repeat::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (repeat::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // length
+  //
+  if (i.length ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "length",
+        e));
+
+    a << ::xml_schema::as_double(*i.length ());
+  }
+
+  // distance
+  //
+  if (i.distance ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "distance",
+        e));
+
+    a << ::xml_schema::as_double(*i.distance ());
+  }
+
+  // tStart
+  //
+  if (i.tStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "tStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.tStart ());
+  }
+
+  // tEnd
+  //
+  if (i.tEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "tEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.tEnd ());
+  }
+
+  // widthStart
+  //
+  if (i.widthStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "widthStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.widthStart ());
+  }
+
+  // widthEnd
+  //
+  if (i.widthEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "widthEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.widthEnd ());
+  }
+
+  // heightStart
+  //
+  if (i.heightStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "heightStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.heightStart ());
+  }
+
+  // heightEnd
+  //
+  if (i.heightEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "heightEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.heightEnd ());
+  }
+
+  // zOffsetStart
+  //
+  if (i.zOffsetStart ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffsetStart",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffsetStart ());
+  }
+
+  // zOffsetEnd
+  //
+  if (i.zOffsetEnd ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "zOffsetEnd",
+        e));
+
+    a << ::xml_schema::as_double(*i.zOffsetEnd ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const outline& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // cornerRoad
+  //
+  for (outline::cornerRoad_const_iterator
+       b (i.cornerRoad ().begin ()), n (i.cornerRoad ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "cornerRoad",
+        e));
+
+    s << *b;
+  }
+
+  // cornerLocal
+  //
+  for (outline::cornerLocal_const_iterator
+       b (i.cornerLocal ().begin ()), n (i.cornerLocal ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "cornerLocal",
+        e));
+
+    s << *b;
+  }
+
+  // userData
+  //
+  for (outline::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (outline::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const material1& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (material1::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (material1::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // surface
+  //
+  if (i.surface ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "surface",
+        e));
+
+    a << *i.surface ();
+  }
+
+  // friction
+  //
+  if (i.friction ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "friction",
+        e));
+
+    a << ::xml_schema::as_double(*i.friction ());
+  }
+
+  // roughness
+  //
+  if (i.roughness ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "roughness",
+        e));
+
+    a << ::xml_schema::as_double(*i.roughness ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const dependency& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (dependency::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (dependency::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // type
+  //
+  if (i.type ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "type",
+        e));
+
+    a << *i.type ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const mainTrack& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // dir
+  //
+  if (i.dir ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dir",
+        e));
+
+    a << *i.dir ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const sideTrack& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // dir
+  //
+  if (i.dir ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dir",
+        e));
+
+    a << *i.dir ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const partner& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // name
+  //
+  if (i.name ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "name",
+        e));
+
+    a << *i.name ();
+  }
+
+  // id
+  //
+  if (i.id ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "id",
+        e));
+
+    a << *i.id ();
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const cornerRoad& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (cornerRoad::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (cornerRoad::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // s
+  //
+  if (i.s ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "s",
+        e));
+
+    a << ::xml_schema::as_double(*i.s ());
+  }
+
+  // t
+  //
+  if (i.t ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "t",
+        e));
+
+    a << ::xml_schema::as_double(*i.t ());
+  }
+
+  // dz
+  //
+  if (i.dz ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "dz",
+        e));
+
+    a << ::xml_schema::as_double(*i.dz ());
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+}
+
+void
+operator<< (::xercesc::DOMElement& e, const cornerLocal& i)
+{
+  e << static_cast< const ::xml_schema::type& > (i);
+
+  // userData
+  //
+  for (cornerLocal::userData_const_iterator
+       b (i.userData ().begin ()), n (i.userData ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "userData",
+        e));
+
+    s << *b;
+  }
+
+  // include
+  //
+  for (cornerLocal::include_const_iterator
+       b (i.include ().begin ()), n (i.include ().end ());
+       b != n; ++b)
+  {
+    ::xercesc::DOMElement& s (
+      ::xsd::cxx::xml::dom::create_element (
+        "include",
+        e));
+
+    s << *b;
+  }
+
+  // u
+  //
+  if (i.u ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "u",
+        e));
+
+    a << ::xml_schema::as_double(*i.u ());
+  }
+
+  // v
+  //
+  if (i.v ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "v",
+        e));
+
+    a << ::xml_schema::as_double(*i.v ());
+  }
+
+  // z
+  //
+  if (i.z ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "z",
+        e));
+
+    a << ::xml_schema::as_double(*i.z ());
+  }
+
+  // height
+  //
+  if (i.height ())
+  {
+    ::xercesc::DOMAttr& a (
+      ::xsd::cxx::xml::dom::create_attribute (
+        "height",
+        e));
+
+    a << ::xml_schema::as_double(*i.height ());
+  }
+}
+
+#include <xsd/cxx/post.hxx>
+
+// Begin epilogue.
+//
+//
+// End epilogue.
+
diff --git a/src/xml/OpenDRIVE_1.4H.hxx b/src/xml/OpenDRIVE_1.4H.hxx
new file mode 100644
index 0000000..b292126
--- /dev/null
+++ b/src/xml/OpenDRIVE_1.4H.hxx
@@ -0,0 +1,15776 @@
+// Copyright (c) 2005-2014 Code Synthesis Tools CC
+//
+// This program was generated by CodeSynthesis XSD, an XML Schema to
+// C++ data binding compiler.
+//
+// This program is free software; you can redistribute it and/or modify
+// it under the terms of the GNU General Public License version 2 as
+// published by the Free Software Foundation.
+//
+// This program is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with this program; if not, write to the Free Software
+// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+//
+// In addition, as a special exception, Code Synthesis Tools CC gives
+// permission to link this program with the Xerces-C++ library (or with
+// modified versions of Xerces-C++ that use the same license as Xerces-C++),
+// and distribute linked combinations including the two. You must obey
+// the GNU General Public License version 2 in all respects for all of
+// the code used other than Xerces-C++. If you modify this copy of the
+// program, you may extend this exception to your version of the program,
+// but you are not obligated to do so. If you do not wish to do so, delete
+// this exception statement from your version.
+//
+// Furthermore, Code Synthesis Tools CC makes a special exception for
+// the Free/Libre and Open Source Software (FLOSS) which is described
+// in the accompanying FLOSSE file.
+//
+
+#ifndef OPEN_DRIVE_1_4H_HXX
+#define OPEN_DRIVE_1_4H_HXX
+
+#ifndef XSD_CXX11
+#define XSD_CXX11
+#endif
+
+#ifndef XSD_USE_CHAR
+#define XSD_USE_CHAR
+#endif
+
+#ifndef XSD_CXX_TREE_USE_CHAR
+#define XSD_CXX_TREE_USE_CHAR
+#endif
+
+// Begin prologue.
+//
+//
+// End prologue.
+
+#include <xsd/cxx/config.hxx>
+
+#if (XSD_INT_VERSION != 4000000L)
+#error XSD runtime version mismatch
+#endif
+
+#include <xsd/cxx/pre.hxx>
+
+#include <xsd/cxx/xml/char-utf8.hxx>
+
+#include <xsd/cxx/tree/exceptions.hxx>
+#include <xsd/cxx/tree/elements.hxx>
+#include <xsd/cxx/tree/types.hxx>
+
+#include <xsd/cxx/xml/error-handler.hxx>
+
+#include <xsd/cxx/xml/dom/auto-ptr.hxx>
+
+#include <xsd/cxx/tree/parsing.hxx>
+#include <xsd/cxx/tree/parsing/byte.hxx>
+#include <xsd/cxx/tree/parsing/unsigned-byte.hxx>
+#include <xsd/cxx/tree/parsing/short.hxx>
+#include <xsd/cxx/tree/parsing/unsigned-short.hxx>
+#include <xsd/cxx/tree/parsing/int.hxx>
+#include <xsd/cxx/tree/parsing/unsigned-int.hxx>
+#include <xsd/cxx/tree/parsing/long.hxx>
+#include <xsd/cxx/tree/parsing/unsigned-long.hxx>
+#include <xsd/cxx/tree/parsing/boolean.hxx>
+#include <xsd/cxx/tree/parsing/float.hxx>
+#include <xsd/cxx/tree/parsing/double.hxx>
+#include <xsd/cxx/tree/parsing/decimal.hxx>
+
+#include <xsd/cxx/xml/dom/serialization-header.hxx>
+#include <xsd/cxx/tree/serialization.hxx>
+#include <xsd/cxx/tree/serialization/byte.hxx>
+#include <xsd/cxx/tree/serialization/unsigned-byte.hxx>
+#include <xsd/cxx/tree/serialization/short.hxx>
+#include <xsd/cxx/tree/serialization/unsigned-short.hxx>
+#include <xsd/cxx/tree/serialization/int.hxx>
+#include <xsd/cxx/tree/serialization/unsigned-int.hxx>
+#include <xsd/cxx/tree/serialization/long.hxx>
+#include <xsd/cxx/tree/serialization/unsigned-long.hxx>
+#include <xsd/cxx/tree/serialization/boolean.hxx>
+#include <xsd/cxx/tree/serialization/float.hxx>
+#include <xsd/cxx/tree/serialization/double.hxx>
+#include <xsd/cxx/tree/serialization/decimal.hxx>
+
+namespace xml_schema
+{
+  // anyType and anySimpleType.
+  //
+  typedef ::xsd::cxx::tree::type type;
+  typedef ::xsd::cxx::tree::simple_type< char, type > simple_type;
+  typedef ::xsd::cxx::tree::type container;
+
+  // 8-bit
+  //
+  typedef signed char byte;
+  typedef unsigned char unsigned_byte;
+
+  // 16-bit
+  //
+  typedef short short_;
+  typedef unsigned short unsigned_short;
+
+  // 32-bit
+  //
+  typedef int int_;
+  typedef unsigned int unsigned_int;
+
+  // 64-bit
+  //
+  typedef long long long_;
+  typedef unsigned long long unsigned_long;
+
+  // Supposed to be arbitrary-length integral types.
+  //
+  typedef long long integer;
+  typedef long long non_positive_integer;
+  typedef unsigned long long non_negative_integer;
+  typedef unsigned long long positive_integer;
+  typedef long long negative_integer;
+
+  // Boolean.
+  //
+  typedef bool boolean;
+
+  // Floating-point types.
+  //
+  typedef float float_;
+  typedef double double_;
+  typedef double decimal;
+
+  // String types.
+  //
+  typedef ::xsd::cxx::tree::string< char, simple_type > string;
+  typedef ::xsd::cxx::tree::normalized_string< char, string > normalized_string;
+  typedef ::xsd::cxx::tree::token< char, normalized_string > token;
+  typedef ::xsd::cxx::tree::name< char, token > name;
+  typedef ::xsd::cxx::tree::nmtoken< char, token > nmtoken;
+  typedef ::xsd::cxx::tree::nmtokens< char, simple_type, nmtoken > nmtokens;
+  typedef ::xsd::cxx::tree::ncname< char, name > ncname;
+  typedef ::xsd::cxx::tree::language< char, token > language;
+
+  // ID/IDREF.
+  //
+  typedef ::xsd::cxx::tree::id< char, ncname > id;
+  typedef ::xsd::cxx::tree::idref< char, ncname, type > idref;
+  typedef ::xsd::cxx::tree::idrefs< char, simple_type, idref > idrefs;
+
+  // URI.
+  //
+  typedef ::xsd::cxx::tree::uri< char, simple_type > uri;
+
+  // Qualified name.
+  //
+  typedef ::xsd::cxx::tree::qname< char, simple_type, uri, ncname > qname;
+
+  // Binary.
+  //
+  typedef ::xsd::cxx::tree::buffer< char > buffer;
+  typedef ::xsd::cxx::tree::base64_binary< char, simple_type > base64_binary;
+  typedef ::xsd::cxx::tree::hex_binary< char, simple_type > hex_binary;
+
+  // Date/time.
+  //
+  typedef ::xsd::cxx::tree::time_zone time_zone;
+  typedef ::xsd::cxx::tree::date< char, simple_type > date;
+  typedef ::xsd::cxx::tree::date_time< char, simple_type > date_time;
+  typedef ::xsd::cxx::tree::duration< char, simple_type > duration;
+  typedef ::xsd::cxx::tree::gday< char, simple_type > gday;
+  typedef ::xsd::cxx::tree::gmonth< char, simple_type > gmonth;
+  typedef ::xsd::cxx::tree::gmonth_day< char, simple_type > gmonth_day;
+  typedef ::xsd::cxx::tree::gyear< char, simple_type > gyear;
+  typedef ::xsd::cxx::tree::gyear_month< char, simple_type > gyear_month;
+  typedef ::xsd::cxx::tree::time< char, simple_type > time;
+
+  // Entity.
+  //
+  typedef ::xsd::cxx::tree::entity< char, ncname > entity;
+  typedef ::xsd::cxx::tree::entities< char, simple_type, entity > entities;
+
+  typedef ::xsd::cxx::tree::content_order content_order;
+  // Namespace information and list stream. Used in
+  // serialization functions.
+  //
+  typedef ::xsd::cxx::xml::dom::namespace_info< char > namespace_info;
+  typedef ::xsd::cxx::xml::dom::namespace_infomap< char > namespace_infomap;
+  typedef ::xsd::cxx::tree::list_stream< char > list_stream;
+  typedef ::xsd::cxx::tree::as_double< double_ > as_double;
+  typedef ::xsd::cxx::tree::as_decimal< decimal > as_decimal;
+  typedef ::xsd::cxx::tree::facet facet;
+
+  // Flags and properties.
+  //
+  typedef ::xsd::cxx::tree::flags flags;
+  typedef ::xsd::cxx::tree::properties< char > properties;
+
+  // Parsing/serialization diagnostics.
+  //
+  typedef ::xsd::cxx::tree::severity severity;
+  typedef ::xsd::cxx::tree::error< char > error;
+  typedef ::xsd::cxx::tree::diagnostics< char > diagnostics;
+
+  // Exceptions.
+  //
+  typedef ::xsd::cxx::tree::exception< char > exception;
+  typedef ::xsd::cxx::tree::bounds< char > bounds;
+  typedef ::xsd::cxx::tree::duplicate_id< char > duplicate_id;
+  typedef ::xsd::cxx::tree::parsing< char > parsing;
+  typedef ::xsd::cxx::tree::expected_element< char > expected_element;
+  typedef ::xsd::cxx::tree::unexpected_element< char > unexpected_element;
+  typedef ::xsd::cxx::tree::expected_attribute< char > expected_attribute;
+  typedef ::xsd::cxx::tree::unexpected_enumerator< char > unexpected_enumerator;
+  typedef ::xsd::cxx::tree::expected_text_content< char > expected_text_content;
+  typedef ::xsd::cxx::tree::no_prefix_mapping< char > no_prefix_mapping;
+  typedef ::xsd::cxx::tree::serialization< char > serialization;
+
+  // Error handler callback interface.
+  //
+  typedef ::xsd::cxx::xml::error_handler< char > error_handler;
+
+  // DOM interaction.
+  //
+  namespace dom
+  {
+    // Automatic pointer for DOMDocument.
+    //
+    using ::xsd::cxx::xml::dom::unique_ptr;
+
+#ifndef XSD_CXX_TREE_TREE_NODE_KEY__XML_SCHEMA
+#define XSD_CXX_TREE_TREE_NODE_KEY__XML_SCHEMA
+    // DOM user data key for back pointers to tree nodes.
+    //
+    const XMLCh* const tree_node_key = ::xsd::cxx::tree::user_data_keys::node;
+#endif
+  }
+}
+
+// Forward declarations.
+//
+class elementType;
+class max;
+class contactPoint;
+class side;
+class direction;
+class roadType;
+class unit;
+class pRange;
+class crossfallSide;
+class singleSide;
+class laneType;
+class roadmarkType;
+class weight;
+class color;
+class restriction;
+class laneChange;
+class rule;
+class orientation;
+class tunnelType;
+class bridgeType;
+class parkingSpace_access;
+class parkingSpacemarkingSide;
+class dynamic;
+class surfaceOrientation;
+class mode;
+class purpose;
+class position;
+class dir;
+class junctionGroupType;
+class stationType;
+class userData;
+class include;
+class laneValidity;
+class parkingSpace;
+class lane;
+class centerLane;
+class OpenDRIVE;
+class max_member;
+class max_member1;
+class marking;
+class lane_link;
+class width;
+class border;
+class roadMark;
+class material;
+class visibility;
+class speed;
+class access1;
+class height;
+class rule1;
+class link1;
+class roadMark1;
+class header;
+class road;
+class controller;
+class junction;
+class junctionGroup;
+class station;
+class predecessor;
+class successor;
+class type;
+class type1;
+class link2;
+class type2;
+class planView;
+class elevationProfile;
+class lateralProfile;
+class lanes;
+class objects;
+class signals;
+class surface;
+class railroad;
+class control;
+class connection;
+class priority;
+class controller1;
+class junctionReference;
+class platform;
+class line;
+class predecessor1;
+class successor1;
+class neighbor;
+class speed1;
+class geometry;
+class elevation;
+class superelevation;
+class crossfall;
+class shape;
+class laneOffset;
+class laneSection;
+class object;
+class objectReference;
+class tunnel;
+class bridge;
+class signal;
+class signalReference;
+class CRG;
+class switch_;
+class laneLink;
+class segment;
+class line1;
+class spiral;
+class arc;
+class poly3;
+class paramPoly3;
+class left;
+class center;
+class right;
+class repeat;
+class outline;
+class material1;
+class dependency;
+class mainTrack;
+class sideTrack;
+class partner;
+class cornerRoad;
+class cornerLocal;
+
+#include <memory>    // ::std::unique_ptr
+#include <limits>    // std::numeric_limits
+#include <algorithm> // std::binary_search
+#include <utility>   // std::move
+
+#include <xsd/cxx/xml/char-utf8.hxx>
+
+#include <xsd/cxx/tree/exceptions.hxx>
+#include <xsd/cxx/tree/elements.hxx>
+#include <xsd/cxx/tree/containers.hxx>
+#include <xsd/cxx/tree/list.hxx>
+
+#include <xsd/cxx/xml/dom/parsing-header.hxx>
+
+class elementType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    road,
+    junction
+  };
+
+  elementType (value v);
+
+  elementType (const char* v);
+
+  elementType (const ::std::string& v);
+
+  elementType (const ::xml_schema::string& v);
+
+  elementType (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  elementType (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  elementType (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  elementType (const elementType& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual elementType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  elementType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_elementType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_elementType_convert () const;
+
+  public:
+  static const char* const _xsd_elementType_literals_[2];
+  static const value _xsd_elementType_indexes_[2];
+};
+
+class max: public ::xml_schema::string
+{
+  public:
+
+  max (const char* v);
+
+  max (const ::std::string& v);
+
+  max (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  max (const ::xercesc::DOMAttr& a,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  max (const ::std::string& s,
+       const ::xercesc::DOMElement* e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  max (const max& x,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  virtual max*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+};
+
+class contactPoint: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    start,
+    end
+  };
+
+  contactPoint (value v);
+
+  contactPoint (const char* v);
+
+  contactPoint (const ::std::string& v);
+
+  contactPoint (const ::xml_schema::string& v);
+
+  contactPoint (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  contactPoint (const ::xercesc::DOMAttr& a,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  contactPoint (const ::std::string& s,
+                const ::xercesc::DOMElement* e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  contactPoint (const contactPoint& x,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  virtual contactPoint*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  contactPoint&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_contactPoint_convert ();
+  }
+
+  protected:
+  value
+  _xsd_contactPoint_convert () const;
+
+  public:
+  static const char* const _xsd_contactPoint_literals_[2];
+  static const value _xsd_contactPoint_indexes_[2];
+};
+
+class side: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    left,
+    right
+  };
+
+  side (value v);
+
+  side (const char* v);
+
+  side (const ::std::string& v);
+
+  side (const ::xml_schema::string& v);
+
+  side (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  side (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  side (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  side (const side& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual side*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  side&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_side_convert ();
+  }
+
+  protected:
+  value
+  _xsd_side_convert () const;
+
+  public:
+  static const char* const _xsd_side_literals_[2];
+  static const value _xsd_side_indexes_[2];
+};
+
+class direction: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    same,
+    opposite
+  };
+
+  direction (value v);
+
+  direction (const char* v);
+
+  direction (const ::std::string& v);
+
+  direction (const ::xml_schema::string& v);
+
+  direction (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  direction (const ::xercesc::DOMAttr& a,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  direction (const ::std::string& s,
+             const ::xercesc::DOMElement* e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  direction (const direction& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual direction*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  direction&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_direction_convert ();
+  }
+
+  protected:
+  value
+  _xsd_direction_convert () const;
+
+  public:
+  static const char* const _xsd_direction_literals_[2];
+  static const value _xsd_direction_indexes_[2];
+};
+
+class roadType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    unknown,
+    rural,
+    motorway,
+    town,
+    lowSpeed,
+    pedestrian,
+    bicycle
+  };
+
+  roadType (value v);
+
+  roadType (const char* v);
+
+  roadType (const ::std::string& v);
+
+  roadType (const ::xml_schema::string& v);
+
+  roadType (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  roadType (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  roadType (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  roadType (const roadType& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual roadType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  roadType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_roadType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_roadType_convert () const;
+
+  public:
+  static const char* const _xsd_roadType_literals_[7];
+  static const value _xsd_roadType_indexes_[7];
+};
+
+class unit: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    m,
+    km,
+    ft,
+    mile,
+    m_s,
+    mph,
+    km_h,
+    kg,
+    t,
+    cxx_
+  };
+
+  unit (value v);
+
+  unit (const char* v);
+
+  unit (const ::std::string& v);
+
+  unit (const ::xml_schema::string& v);
+
+  unit (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  unit (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  unit (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  unit (const unit& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual unit*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  unit&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_unit_convert ();
+  }
+
+  protected:
+  value
+  _xsd_unit_convert () const;
+
+  public:
+  static const char* const _xsd_unit_literals_[10];
+  static const value _xsd_unit_indexes_[10];
+};
+
+class pRange: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    arcLength,
+    normalized
+  };
+
+  pRange (value v);
+
+  pRange (const char* v);
+
+  pRange (const ::std::string& v);
+
+  pRange (const ::xml_schema::string& v);
+
+  pRange (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  pRange (const ::xercesc::DOMAttr& a,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  pRange (const ::std::string& s,
+          const ::xercesc::DOMElement* e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  pRange (const pRange& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual pRange*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  pRange&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_pRange_convert ();
+  }
+
+  protected:
+  value
+  _xsd_pRange_convert () const;
+
+  public:
+  static const char* const _xsd_pRange_literals_[2];
+  static const value _xsd_pRange_indexes_[2];
+};
+
+class crossfallSide: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    left,
+    right,
+    both
+  };
+
+  crossfallSide (value v);
+
+  crossfallSide (const char* v);
+
+  crossfallSide (const ::std::string& v);
+
+  crossfallSide (const ::xml_schema::string& v);
+
+  crossfallSide (const ::xercesc::DOMElement& e,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  crossfallSide (const ::xercesc::DOMAttr& a,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  crossfallSide (const ::std::string& s,
+                 const ::xercesc::DOMElement* e,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  crossfallSide (const crossfallSide& x,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  virtual crossfallSide*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  crossfallSide&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_crossfallSide_convert ();
+  }
+
+  protected:
+  value
+  _xsd_crossfallSide_convert () const;
+
+  public:
+  static const char* const _xsd_crossfallSide_literals_[3];
+  static const value _xsd_crossfallSide_indexes_[3];
+};
+
+class singleSide: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    true_,
+    false_
+  };
+
+  singleSide (value v);
+
+  singleSide (const char* v);
+
+  singleSide (const ::std::string& v);
+
+  singleSide (const ::xml_schema::string& v);
+
+  singleSide (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  singleSide (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  singleSide (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  singleSide (const singleSide& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual singleSide*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  singleSide&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_singleSide_convert ();
+  }
+
+  protected:
+  value
+  _xsd_singleSide_convert () const;
+
+  public:
+  static const char* const _xsd_singleSide_literals_[2];
+  static const value _xsd_singleSide_indexes_[2];
+};
+
+class laneType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    none,
+    driving,
+    stop,
+    shoulder,
+    biking,
+    sidewalk,
+    border,
+    restricted,
+    parking,
+    bidirectional,
+    median,
+    special1,
+    special2,
+    special3,
+    roadWorks,
+    tram,
+    rail,
+    entry,
+    exit,
+    offRamp,
+    onRamp
+  };
+
+  laneType (value v);
+
+  laneType (const char* v);
+
+  laneType (const ::std::string& v);
+
+  laneType (const ::xml_schema::string& v);
+
+  laneType (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  laneType (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  laneType (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  laneType (const laneType& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual laneType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_laneType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_laneType_convert () const;
+
+  public:
+  static const char* const _xsd_laneType_literals_[21];
+  static const value _xsd_laneType_indexes_[21];
+};
+
+class roadmarkType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    none,
+    solid,
+    broken,
+    solid_solid,
+    solid_broken,
+    broken_solid,
+    broken_broken,
+    botts_dots,
+    grass,
+    curb
+  };
+
+  roadmarkType (value v);
+
+  roadmarkType (const char* v);
+
+  roadmarkType (const ::std::string& v);
+
+  roadmarkType (const ::xml_schema::string& v);
+
+  roadmarkType (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  roadmarkType (const ::xercesc::DOMAttr& a,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  roadmarkType (const ::std::string& s,
+                const ::xercesc::DOMElement* e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  roadmarkType (const roadmarkType& x,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  virtual roadmarkType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  roadmarkType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_roadmarkType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_roadmarkType_convert () const;
+
+  public:
+  static const char* const _xsd_roadmarkType_literals_[10];
+  static const value _xsd_roadmarkType_indexes_[10];
+};
+
+class weight: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    standard,
+    bold
+  };
+
+  weight (value v);
+
+  weight (const char* v);
+
+  weight (const ::std::string& v);
+
+  weight (const ::xml_schema::string& v);
+
+  weight (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  weight (const ::xercesc::DOMAttr& a,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  weight (const ::std::string& s,
+          const ::xercesc::DOMElement* e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  weight (const weight& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual weight*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  weight&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_weight_convert ();
+  }
+
+  protected:
+  value
+  _xsd_weight_convert () const;
+
+  public:
+  static const char* const _xsd_weight_literals_[2];
+  static const value _xsd_weight_indexes_[2];
+};
+
+class color: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    standard,
+    blue,
+    green,
+    red,
+    white,
+    yellow
+  };
+
+  color (value v);
+
+  color (const char* v);
+
+  color (const ::std::string& v);
+
+  color (const ::xml_schema::string& v);
+
+  color (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  color (const ::xercesc::DOMAttr& a,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  color (const ::std::string& s,
+         const ::xercesc::DOMElement* e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  color (const color& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual color*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  color&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_color_convert ();
+  }
+
+  protected:
+  value
+  _xsd_color_convert () const;
+
+  public:
+  static const char* const _xsd_color_literals_[6];
+  static const value _xsd_color_indexes_[6];
+};
+
+class restriction: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    simulator,
+    autonomous_traffic,
+    pedestrian,
+    none
+  };
+
+  restriction (value v);
+
+  restriction (const char* v);
+
+  restriction (const ::std::string& v);
+
+  restriction (const ::xml_schema::string& v);
+
+  restriction (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  restriction (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  restriction (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  restriction (const restriction& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual restriction*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  restriction&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_restriction_convert ();
+  }
+
+  protected:
+  value
+  _xsd_restriction_convert () const;
+
+  public:
+  static const char* const _xsd_restriction_literals_[4];
+  static const value _xsd_restriction_indexes_[4];
+};
+
+class laneChange: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    increase,
+    decrease,
+    both,
+    none
+  };
+
+  laneChange (value v);
+
+  laneChange (const char* v);
+
+  laneChange (const ::std::string& v);
+
+  laneChange (const ::xml_schema::string& v);
+
+  laneChange (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  laneChange (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  laneChange (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  laneChange (const laneChange& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual laneChange*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneChange&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_laneChange_convert ();
+  }
+
+  protected:
+  value
+  _xsd_laneChange_convert () const;
+
+  public:
+  static const char* const _xsd_laneChange_literals_[4];
+  static const value _xsd_laneChange_indexes_[4];
+};
+
+class rule: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    no_passing,
+    caution,
+    none
+  };
+
+  rule (value v);
+
+  rule (const char* v);
+
+  rule (const ::std::string& v);
+
+  rule (const ::xml_schema::string& v);
+
+  rule (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  rule (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  rule (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  rule (const rule& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual rule*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  rule&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_rule_convert ();
+  }
+
+  protected:
+  value
+  _xsd_rule_convert () const;
+
+  public:
+  static const char* const _xsd_rule_literals_[3];
+  static const value _xsd_rule_indexes_[3];
+};
+
+class orientation: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    cxx_,
+    cxx_1,
+    none
+  };
+
+  orientation (value v);
+
+  orientation (const char* v);
+
+  orientation (const ::std::string& v);
+
+  orientation (const ::xml_schema::string& v);
+
+  orientation (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  orientation (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  orientation (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  orientation (const orientation& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual orientation*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  orientation&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_orientation_convert ();
+  }
+
+  protected:
+  value
+  _xsd_orientation_convert () const;
+
+  public:
+  static const char* const _xsd_orientation_literals_[3];
+  static const value _xsd_orientation_indexes_[3];
+};
+
+class tunnelType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    standard,
+    underpass
+  };
+
+  tunnelType (value v);
+
+  tunnelType (const char* v);
+
+  tunnelType (const ::std::string& v);
+
+  tunnelType (const ::xml_schema::string& v);
+
+  tunnelType (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  tunnelType (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  tunnelType (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  tunnelType (const tunnelType& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual tunnelType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  tunnelType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_tunnelType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_tunnelType_convert () const;
+
+  public:
+  static const char* const _xsd_tunnelType_literals_[2];
+  static const value _xsd_tunnelType_indexes_[2];
+};
+
+class bridgeType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    concrete,
+    steel,
+    brick,
+    wood
+  };
+
+  bridgeType (value v);
+
+  bridgeType (const char* v);
+
+  bridgeType (const ::std::string& v);
+
+  bridgeType (const ::xml_schema::string& v);
+
+  bridgeType (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  bridgeType (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  bridgeType (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  bridgeType (const bridgeType& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual bridgeType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  bridgeType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_bridgeType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_bridgeType_convert () const;
+
+  public:
+  static const char* const _xsd_bridgeType_literals_[4];
+  static const value _xsd_bridgeType_indexes_[4];
+};
+
+class parkingSpace_access: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    all,
+    car,
+    women,
+    handicapped,
+    bus,
+    truck,
+    electric,
+    residents
+  };
+
+  parkingSpace_access (value v);
+
+  parkingSpace_access (const char* v);
+
+  parkingSpace_access (const ::std::string& v);
+
+  parkingSpace_access (const ::xml_schema::string& v);
+
+  parkingSpace_access (const ::xercesc::DOMElement& e,
+                       ::xml_schema::flags f = 0,
+                       ::xml_schema::container* c = 0);
+
+  parkingSpace_access (const ::xercesc::DOMAttr& a,
+                       ::xml_schema::flags f = 0,
+                       ::xml_schema::container* c = 0);
+
+  parkingSpace_access (const ::std::string& s,
+                       const ::xercesc::DOMElement* e,
+                       ::xml_schema::flags f = 0,
+                       ::xml_schema::container* c = 0);
+
+  parkingSpace_access (const parkingSpace_access& x,
+                       ::xml_schema::flags f = 0,
+                       ::xml_schema::container* c = 0);
+
+  virtual parkingSpace_access*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  parkingSpace_access&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_parkingSpace_access_convert ();
+  }
+
+  protected:
+  value
+  _xsd_parkingSpace_access_convert () const;
+
+  public:
+  static const char* const _xsd_parkingSpace_access_literals_[8];
+  static const value _xsd_parkingSpace_access_indexes_[8];
+};
+
+class parkingSpacemarkingSide: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    front,
+    rear,
+    left,
+    right
+  };
+
+  parkingSpacemarkingSide (value v);
+
+  parkingSpacemarkingSide (const char* v);
+
+  parkingSpacemarkingSide (const ::std::string& v);
+
+  parkingSpacemarkingSide (const ::xml_schema::string& v);
+
+  parkingSpacemarkingSide (const ::xercesc::DOMElement& e,
+                           ::xml_schema::flags f = 0,
+                           ::xml_schema::container* c = 0);
+
+  parkingSpacemarkingSide (const ::xercesc::DOMAttr& a,
+                           ::xml_schema::flags f = 0,
+                           ::xml_schema::container* c = 0);
+
+  parkingSpacemarkingSide (const ::std::string& s,
+                           const ::xercesc::DOMElement* e,
+                           ::xml_schema::flags f = 0,
+                           ::xml_schema::container* c = 0);
+
+  parkingSpacemarkingSide (const parkingSpacemarkingSide& x,
+                           ::xml_schema::flags f = 0,
+                           ::xml_schema::container* c = 0);
+
+  virtual parkingSpacemarkingSide*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  parkingSpacemarkingSide&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_parkingSpacemarkingSide_convert ();
+  }
+
+  protected:
+  value
+  _xsd_parkingSpacemarkingSide_convert () const;
+
+  public:
+  static const char* const _xsd_parkingSpacemarkingSide_literals_[4];
+  static const value _xsd_parkingSpacemarkingSide_indexes_[4];
+};
+
+class dynamic: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    yes,
+    no
+  };
+
+  dynamic (value v);
+
+  dynamic (const char* v);
+
+  dynamic (const ::std::string& v);
+
+  dynamic (const ::xml_schema::string& v);
+
+  dynamic (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  dynamic (const ::xercesc::DOMAttr& a,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  dynamic (const ::std::string& s,
+           const ::xercesc::DOMElement* e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  dynamic (const dynamic& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual dynamic*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  dynamic&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_dynamic_convert ();
+  }
+
+  protected:
+  value
+  _xsd_dynamic_convert () const;
+
+  public:
+  static const char* const _xsd_dynamic_literals_[2];
+  static const value _xsd_dynamic_indexes_[2];
+};
+
+class surfaceOrientation: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    same,
+    opposite
+  };
+
+  surfaceOrientation (value v);
+
+  surfaceOrientation (const char* v);
+
+  surfaceOrientation (const ::std::string& v);
+
+  surfaceOrientation (const ::xml_schema::string& v);
+
+  surfaceOrientation (const ::xercesc::DOMElement& e,
+                      ::xml_schema::flags f = 0,
+                      ::xml_schema::container* c = 0);
+
+  surfaceOrientation (const ::xercesc::DOMAttr& a,
+                      ::xml_schema::flags f = 0,
+                      ::xml_schema::container* c = 0);
+
+  surfaceOrientation (const ::std::string& s,
+                      const ::xercesc::DOMElement* e,
+                      ::xml_schema::flags f = 0,
+                      ::xml_schema::container* c = 0);
+
+  surfaceOrientation (const surfaceOrientation& x,
+                      ::xml_schema::flags f = 0,
+                      ::xml_schema::container* c = 0);
+
+  virtual surfaceOrientation*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  surfaceOrientation&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_surfaceOrientation_convert ();
+  }
+
+  protected:
+  value
+  _xsd_surfaceOrientation_convert () const;
+
+  public:
+  static const char* const _xsd_surfaceOrientation_literals_[2];
+  static const value _xsd_surfaceOrientation_indexes_[2];
+};
+
+class mode: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    attached,
+    attached0,
+    genuine
+  };
+
+  mode (value v);
+
+  mode (const char* v);
+
+  mode (const ::std::string& v);
+
+  mode (const ::xml_schema::string& v);
+
+  mode (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  mode (const ::xercesc::DOMAttr& a,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  mode (const ::std::string& s,
+        const ::xercesc::DOMElement* e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  mode (const mode& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual mode*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  mode&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_mode_convert ();
+  }
+
+  protected:
+  value
+  _xsd_mode_convert () const;
+
+  public:
+  static const char* const _xsd_mode_literals_[3];
+  static const value _xsd_mode_indexes_[3];
+};
+
+class purpose: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    elevation,
+    friction
+  };
+
+  purpose (value v);
+
+  purpose (const char* v);
+
+  purpose (const ::std::string& v);
+
+  purpose (const ::xml_schema::string& v);
+
+  purpose (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  purpose (const ::xercesc::DOMAttr& a,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  purpose (const ::std::string& s,
+           const ::xercesc::DOMElement* e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  purpose (const purpose& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual purpose*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  purpose&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_purpose_convert ();
+  }
+
+  protected:
+  value
+  _xsd_purpose_convert () const;
+
+  public:
+  static const char* const _xsd_purpose_literals_[2];
+  static const value _xsd_purpose_indexes_[2];
+};
+
+class position: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    dynamic,
+    straight,
+    turn
+  };
+
+  position (value v);
+
+  position (const char* v);
+
+  position (const ::std::string& v);
+
+  position (const ::xml_schema::string& v);
+
+  position (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  position (const ::xercesc::DOMAttr& a,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  position (const ::std::string& s,
+            const ::xercesc::DOMElement* e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  position (const position& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual position*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  position&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_position_convert ();
+  }
+
+  protected:
+  value
+  _xsd_position_convert () const;
+
+  public:
+  static const char* const _xsd_position_literals_[3];
+  static const value _xsd_position_indexes_[3];
+};
+
+class dir: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    cxx_,
+    cxx_1
+  };
+
+  dir (value v);
+
+  dir (const char* v);
+
+  dir (const ::std::string& v);
+
+  dir (const ::xml_schema::string& v);
+
+  dir (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  dir (const ::xercesc::DOMAttr& a,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  dir (const ::std::string& s,
+       const ::xercesc::DOMElement* e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  dir (const dir& x,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  virtual dir*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  dir&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_dir_convert ();
+  }
+
+  protected:
+  value
+  _xsd_dir_convert () const;
+
+  public:
+  static const char* const _xsd_dir_literals_[2];
+  static const value _xsd_dir_indexes_[2];
+};
+
+class junctionGroupType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    roundabout,
+    unknown
+  };
+
+  junctionGroupType (value v);
+
+  junctionGroupType (const char* v);
+
+  junctionGroupType (const ::std::string& v);
+
+  junctionGroupType (const ::xml_schema::string& v);
+
+  junctionGroupType (const ::xercesc::DOMElement& e,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  junctionGroupType (const ::xercesc::DOMAttr& a,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  junctionGroupType (const ::std::string& s,
+                     const ::xercesc::DOMElement* e,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  junctionGroupType (const junctionGroupType& x,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  virtual junctionGroupType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  junctionGroupType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_junctionGroupType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_junctionGroupType_convert () const;
+
+  public:
+  static const char* const _xsd_junctionGroupType_literals_[2];
+  static const value _xsd_junctionGroupType_indexes_[2];
+};
+
+class stationType: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    small,
+    medium,
+    large
+  };
+
+  stationType (value v);
+
+  stationType (const char* v);
+
+  stationType (const ::std::string& v);
+
+  stationType (const ::xml_schema::string& v);
+
+  stationType (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  stationType (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  stationType (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  stationType (const stationType& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual stationType*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  stationType&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_stationType_convert ();
+  }
+
+  protected:
+  value
+  _xsd_stationType_convert () const;
+
+  public:
+  static const char* const _xsd_stationType_literals_[3];
+  static const value _xsd_stationType_indexes_[3];
+};
+
+class userData: public ::xml_schema::type
+{
+  public:
+  // code
+  //
+  typedef ::xml_schema::string code_type;
+  typedef ::xsd::cxx::tree::optional< code_type > code_optional;
+  typedef ::xsd::cxx::tree::traits< code_type, char > code_traits;
+
+  const code_optional&
+  code () const;
+
+  code_optional&
+  code ();
+
+  void
+  code (const code_type& x);
+
+  void
+  code (const code_optional& x);
+
+  void
+  code (::std::unique_ptr< code_type > p);
+
+  // value
+  //
+  typedef ::xml_schema::string value_type;
+  typedef ::xsd::cxx::tree::optional< value_type > value_optional;
+  typedef ::xsd::cxx::tree::traits< value_type, char > value_traits;
+
+  const value_optional&
+  value () const;
+
+  value_optional&
+  value ();
+
+  void
+  value (const value_type& x);
+
+  void
+  value (const value_optional& x);
+
+  void
+  value (::std::unique_ptr< value_type > p);
+
+  // Constructors.
+  //
+  userData ();
+
+  userData (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  userData (const userData& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual userData*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  userData&
+  operator= (const userData& x);
+
+  virtual 
+  ~userData ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  code_optional code_;
+  value_optional value_;
+};
+
+class include: public ::xml_schema::type
+{
+  public:
+  // file
+  //
+  typedef ::xml_schema::string file_type;
+  typedef ::xsd::cxx::tree::optional< file_type > file_optional;
+  typedef ::xsd::cxx::tree::traits< file_type, char > file_traits;
+
+  const file_optional&
+  file () const;
+
+  file_optional&
+  file ();
+
+  void
+  file (const file_type& x);
+
+  void
+  file (const file_optional& x);
+
+  void
+  file (::std::unique_ptr< file_type > p);
+
+  // Constructors.
+  //
+  include ();
+
+  include (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  include (const include& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual include*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  include&
+  operator= (const include& x);
+
+  virtual 
+  ~include ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  file_optional file_;
+};
+
+class laneValidity: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // fromLane
+  //
+  typedef ::xml_schema::int_ fromLane_type;
+  typedef ::xsd::cxx::tree::optional< fromLane_type > fromLane_optional;
+  typedef ::xsd::cxx::tree::traits< fromLane_type, char > fromLane_traits;
+
+  const fromLane_optional&
+  fromLane () const;
+
+  fromLane_optional&
+  fromLane ();
+
+  void
+  fromLane (const fromLane_type& x);
+
+  void
+  fromLane (const fromLane_optional& x);
+
+  // toLane
+  //
+  typedef ::xml_schema::int_ toLane_type;
+  typedef ::xsd::cxx::tree::optional< toLane_type > toLane_optional;
+  typedef ::xsd::cxx::tree::traits< toLane_type, char > toLane_traits;
+
+  const toLane_optional&
+  toLane () const;
+
+  toLane_optional&
+  toLane ();
+
+  void
+  toLane (const toLane_type& x);
+
+  void
+  toLane (const toLane_optional& x);
+
+  // Constructors.
+  //
+  laneValidity ();
+
+  laneValidity (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  laneValidity (const laneValidity& x,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  virtual laneValidity*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneValidity&
+  operator= (const laneValidity& x);
+
+  virtual 
+  ~laneValidity ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  fromLane_optional fromLane_;
+  toLane_optional toLane_;
+};
+
+class parkingSpace: public ::xml_schema::type
+{
+  public:
+  // marking
+  //
+  typedef ::marking marking_type;
+  typedef ::xsd::cxx::tree::sequence< marking_type > marking_sequence;
+  typedef marking_sequence::iterator marking_iterator;
+  typedef marking_sequence::const_iterator marking_const_iterator;
+  typedef ::xsd::cxx::tree::traits< marking_type, char > marking_traits;
+
+  const marking_sequence&
+  marking () const;
+
+  marking_sequence&
+  marking ();
+
+  void
+  marking (const marking_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // access
+  //
+  typedef ::parkingSpace_access access_type;
+  typedef ::xsd::cxx::tree::optional< access_type > access_optional;
+  typedef ::xsd::cxx::tree::traits< access_type, char > access_traits;
+
+  const access_optional&
+  parkingSpace_access () const;
+
+  access_optional&
+  parkingSpace_access ();
+
+  void
+  parkingSpace_access (const access_type& x);
+
+  void
+  parkingSpace_access (const access_optional& x);
+
+  void
+  parkingSpace_access (::std::unique_ptr< access_type > p);
+
+  // restrictions
+  //
+  typedef ::xml_schema::string restrictions_type;
+  typedef ::xsd::cxx::tree::optional< restrictions_type > restrictions_optional;
+  typedef ::xsd::cxx::tree::traits< restrictions_type, char > restrictions_traits;
+
+  const restrictions_optional&
+  restrictions () const;
+
+  restrictions_optional&
+  restrictions ();
+
+  void
+  restrictions (const restrictions_type& x);
+
+  void
+  restrictions (const restrictions_optional& x);
+
+  void
+  restrictions (::std::unique_ptr< restrictions_type > p);
+
+  // Constructors.
+  //
+  parkingSpace ();
+
+  parkingSpace (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  parkingSpace (const parkingSpace& x,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  virtual parkingSpace*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  parkingSpace&
+  operator= (const parkingSpace& x);
+
+  virtual 
+  ~parkingSpace ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  marking_sequence marking_;
+  userData_sequence userData_;
+  include_sequence include_;
+  access_optional parkingSpace_access_;
+  restrictions_optional restrictions_;
+};
+
+class lane: public ::xml_schema::type
+{
+  public:
+  // link
+  //
+  typedef ::lane_link link_type;
+  typedef ::xsd::cxx::tree::optional< link_type > link_optional;
+  typedef ::xsd::cxx::tree::traits< link_type, char > link_traits;
+
+  const link_optional&
+  lane_link () const;
+
+  link_optional&
+  lane_link ();
+
+  void
+  lane_link (const link_type& x);
+
+  void
+  lane_link (const link_optional& x);
+
+  void
+  lane_link (::std::unique_ptr< link_type > p);
+
+  // width
+  //
+  typedef ::width width_type;
+  typedef ::xsd::cxx::tree::sequence< width_type > width_sequence;
+  typedef width_sequence::iterator width_iterator;
+  typedef width_sequence::const_iterator width_const_iterator;
+  typedef ::xsd::cxx::tree::traits< width_type, char > width_traits;
+
+  const width_sequence&
+  width () const;
+
+  width_sequence&
+  width ();
+
+  void
+  width (const width_sequence& s);
+
+  // border
+  //
+  typedef ::border border_type;
+  typedef ::xsd::cxx::tree::sequence< border_type > border_sequence;
+  typedef border_sequence::iterator border_iterator;
+  typedef border_sequence::const_iterator border_const_iterator;
+  typedef ::xsd::cxx::tree::traits< border_type, char > border_traits;
+
+  const border_sequence&
+  border () const;
+
+  border_sequence&
+  border ();
+
+  void
+  border (const border_sequence& s);
+
+  // roadMark
+  //
+  typedef ::roadMark roadMark_type;
+  typedef ::xsd::cxx::tree::sequence< roadMark_type > roadMark_sequence;
+  typedef roadMark_sequence::iterator roadMark_iterator;
+  typedef roadMark_sequence::const_iterator roadMark_const_iterator;
+  typedef ::xsd::cxx::tree::traits< roadMark_type, char > roadMark_traits;
+
+  const roadMark_sequence&
+  roadMark () const;
+
+  roadMark_sequence&
+  roadMark ();
+
+  void
+  roadMark (const roadMark_sequence& s);
+
+  // material
+  //
+  typedef ::material material_type;
+  typedef ::xsd::cxx::tree::sequence< material_type > material_sequence;
+  typedef material_sequence::iterator material_iterator;
+  typedef material_sequence::const_iterator material_const_iterator;
+  typedef ::xsd::cxx::tree::traits< material_type, char > material_traits;
+
+  const material_sequence&
+  material () const;
+
+  material_sequence&
+  material ();
+
+  void
+  material (const material_sequence& s);
+
+  // visibility
+  //
+  typedef ::visibility visibility_type;
+  typedef ::xsd::cxx::tree::sequence< visibility_type > visibility_sequence;
+  typedef visibility_sequence::iterator visibility_iterator;
+  typedef visibility_sequence::const_iterator visibility_const_iterator;
+  typedef ::xsd::cxx::tree::traits< visibility_type, char > visibility_traits;
+
+  const visibility_sequence&
+  visibility () const;
+
+  visibility_sequence&
+  visibility ();
+
+  void
+  visibility (const visibility_sequence& s);
+
+  // speed
+  //
+  typedef ::speed speed_type;
+  typedef ::xsd::cxx::tree::sequence< speed_type > speed_sequence;
+  typedef speed_sequence::iterator speed_iterator;
+  typedef speed_sequence::const_iterator speed_const_iterator;
+  typedef ::xsd::cxx::tree::traits< speed_type, char > speed_traits;
+
+  const speed_sequence&
+  speed () const;
+
+  speed_sequence&
+  speed ();
+
+  void
+  speed (const speed_sequence& s);
+
+  // access
+  //
+  typedef ::access1 access_type;
+  typedef ::xsd::cxx::tree::sequence< access_type > access_sequence;
+  typedef access_sequence::iterator access_iterator;
+  typedef access_sequence::const_iterator access_const_iterator;
+  typedef ::xsd::cxx::tree::traits< access_type, char > access_traits;
+
+  const access_sequence&
+  parkingSpace_access () const;
+
+  access_sequence&
+  parkingSpace_access ();
+
+  void
+  parkingSpace_access (const access_sequence& s);
+
+  // height
+  //
+  typedef ::height height_type;
+  typedef ::xsd::cxx::tree::sequence< height_type > height_sequence;
+  typedef height_sequence::iterator height_iterator;
+  typedef height_sequence::const_iterator height_const_iterator;
+  typedef ::xsd::cxx::tree::traits< height_type, char > height_traits;
+
+  const height_sequence&
+  height () const;
+
+  height_sequence&
+  height ();
+
+  void
+  height (const height_sequence& s);
+
+  // rule
+  //
+  typedef ::rule1 rule_type;
+  typedef ::xsd::cxx::tree::sequence< rule_type > rule_sequence;
+  typedef rule_sequence::iterator rule_iterator;
+  typedef rule_sequence::const_iterator rule_const_iterator;
+  typedef ::xsd::cxx::tree::traits< rule_type, char > rule_traits;
+
+  const rule_sequence&
+  rule () const;
+
+  rule_sequence&
+  rule ();
+
+  void
+  rule (const rule_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::int_ id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  // type
+  //
+  typedef ::laneType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // level
+  //
+  typedef ::singleSide level_type;
+  typedef ::xsd::cxx::tree::optional< level_type > level_optional;
+  typedef ::xsd::cxx::tree::traits< level_type, char > level_traits;
+
+  const level_optional&
+  level () const;
+
+  level_optional&
+  level ();
+
+  void
+  level (const level_type& x);
+
+  void
+  level (const level_optional& x);
+
+  void
+  level (::std::unique_ptr< level_type > p);
+
+  // Constructors.
+  //
+  lane ();
+
+  lane (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  lane (const lane& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual lane*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  lane&
+  operator= (const lane& x);
+
+  virtual 
+  ~lane ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  link_optional lane_link_;
+  width_sequence width_;
+  border_sequence border_;
+  roadMark_sequence roadMark_;
+  material_sequence material_;
+  visibility_sequence visibility_;
+  speed_sequence speed_;
+  access_sequence parkingSpace_access_;
+  height_sequence height_;
+  rule_sequence rule_;
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  type_optional type_;
+  level_optional level_;
+};
+
+class centerLane: public ::xml_schema::type
+{
+  public:
+  // link
+  //
+  typedef ::link1 link_type;
+  typedef ::xsd::cxx::tree::optional< link_type > link_optional;
+  typedef ::xsd::cxx::tree::traits< link_type, char > link_traits;
+
+  const link_optional&
+  lane_link () const;
+
+  link_optional&
+  lane_link ();
+
+  void
+  lane_link (const link_type& x);
+
+  void
+  lane_link (const link_optional& x);
+
+  void
+  lane_link (::std::unique_ptr< link_type > p);
+
+  // roadMark
+  //
+  typedef ::roadMark1 roadMark_type;
+  typedef ::xsd::cxx::tree::sequence< roadMark_type > roadMark_sequence;
+  typedef roadMark_sequence::iterator roadMark_iterator;
+  typedef roadMark_sequence::const_iterator roadMark_const_iterator;
+  typedef ::xsd::cxx::tree::traits< roadMark_type, char > roadMark_traits;
+
+  const roadMark_sequence&
+  roadMark () const;
+
+  roadMark_sequence&
+  roadMark ();
+
+  void
+  roadMark (const roadMark_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::int_ id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  // type
+  //
+  typedef ::laneType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // level
+  //
+  typedef ::singleSide level_type;
+  typedef ::xsd::cxx::tree::optional< level_type > level_optional;
+  typedef ::xsd::cxx::tree::traits< level_type, char > level_traits;
+
+  const level_optional&
+  level () const;
+
+  level_optional&
+  level ();
+
+  void
+  level (const level_type& x);
+
+  void
+  level (const level_optional& x);
+
+  void
+  level (::std::unique_ptr< level_type > p);
+
+  // Constructors.
+  //
+  centerLane ();
+
+  centerLane (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  centerLane (const centerLane& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual centerLane*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  centerLane&
+  operator= (const centerLane& x);
+
+  virtual 
+  ~centerLane ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  link_optional lane_link_;
+  roadMark_sequence roadMark_;
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  type_optional type_;
+  level_optional level_;
+};
+
+class OpenDRIVE: public ::xml_schema::type
+{
+  public:
+  // header
+  //
+  typedef ::header header_type;
+  typedef ::xsd::cxx::tree::traits< header_type, char > header_traits;
+
+  const header_type&
+  header () const;
+
+  header_type&
+  header ();
+
+  void
+  header (const header_type& x);
+
+  void
+  header (::std::unique_ptr< header_type > p);
+
+  // road
+  //
+  typedef ::road road_type;
+  typedef ::xsd::cxx::tree::sequence< road_type > road_sequence;
+  typedef road_sequence::iterator road_iterator;
+  typedef road_sequence::const_iterator road_const_iterator;
+  typedef ::xsd::cxx::tree::traits< road_type, char > road_traits;
+
+  const road_sequence&
+  road () const;
+
+  road_sequence&
+  road ();
+
+  void
+  road (const road_sequence& s);
+
+  // controller
+  //
+  typedef ::controller controller_type;
+  typedef ::xsd::cxx::tree::sequence< controller_type > controller_sequence;
+  typedef controller_sequence::iterator controller_iterator;
+  typedef controller_sequence::const_iterator controller_const_iterator;
+  typedef ::xsd::cxx::tree::traits< controller_type, char > controller_traits;
+
+  const controller_sequence&
+  controller () const;
+
+  controller_sequence&
+  controller ();
+
+  void
+  controller (const controller_sequence& s);
+
+  // junction
+  //
+  typedef ::junction junction_type;
+  typedef ::xsd::cxx::tree::sequence< junction_type > junction_sequence;
+  typedef junction_sequence::iterator junction_iterator;
+  typedef junction_sequence::const_iterator junction_const_iterator;
+  typedef ::xsd::cxx::tree::traits< junction_type, char > junction_traits;
+
+  const junction_sequence&
+  junction () const;
+
+  junction_sequence&
+  junction ();
+
+  void
+  junction (const junction_sequence& s);
+
+  // junctionGroup
+  //
+  typedef ::junctionGroup junctionGroup_type;
+  typedef ::xsd::cxx::tree::sequence< junctionGroup_type > junctionGroup_sequence;
+  typedef junctionGroup_sequence::iterator junctionGroup_iterator;
+  typedef junctionGroup_sequence::const_iterator junctionGroup_const_iterator;
+  typedef ::xsd::cxx::tree::traits< junctionGroup_type, char > junctionGroup_traits;
+
+  const junctionGroup_sequence&
+  junctionGroup () const;
+
+  junctionGroup_sequence&
+  junctionGroup ();
+
+  void
+  junctionGroup (const junctionGroup_sequence& s);
+
+  // station
+  //
+  typedef ::station station_type;
+  typedef ::xsd::cxx::tree::sequence< station_type > station_sequence;
+  typedef station_sequence::iterator station_iterator;
+  typedef station_sequence::const_iterator station_const_iterator;
+  typedef ::xsd::cxx::tree::traits< station_type, char > station_traits;
+
+  const station_sequence&
+  station () const;
+
+  station_sequence&
+  station ();
+
+  void
+  station (const station_sequence& s);
+
+  // Constructors.
+  //
+  OpenDRIVE (const header_type&);
+
+  OpenDRIVE (::std::unique_ptr< header_type >);
+
+  OpenDRIVE (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  OpenDRIVE (const OpenDRIVE& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual OpenDRIVE*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  OpenDRIVE&
+  operator= (const OpenDRIVE& x);
+
+  virtual 
+  ~OpenDRIVE ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  ::xsd::cxx::tree::one< header_type > header_;
+  road_sequence road_;
+  controller_sequence controller_;
+  junction_sequence junction_;
+  junctionGroup_sequence junctionGroup_;
+  station_sequence station_;
+};
+
+class max_member: public ::xml_schema::string
+{
+  public:
+  enum value
+  {
+    no_limit,
+    undefined
+  };
+
+  max_member (value v);
+
+  max_member (const char* v);
+
+  max_member (const ::std::string& v);
+
+  max_member (const ::xml_schema::string& v);
+
+  max_member (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  max_member (const ::xercesc::DOMAttr& a,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  max_member (const ::std::string& s,
+              const ::xercesc::DOMElement* e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  max_member (const max_member& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual max_member*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  max_member&
+  operator= (value v);
+
+  virtual
+  operator value () const
+  {
+    return _xsd_max_member_convert ();
+  }
+
+  protected:
+  value
+  _xsd_max_member_convert () const;
+
+  public:
+  static const char* const _xsd_max_member_literals_[2];
+  static const value _xsd_max_member_indexes_[2];
+};
+
+class max_member1: public ::xsd::cxx::tree::fundamental_base< ::xml_schema::integer, char, ::xml_schema::simple_type >
+{
+  public:
+  // Constructors.
+  //
+  max_member1 (const ::xml_schema::integer&);
+
+  max_member1 (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  max_member1 (const ::xercesc::DOMAttr& a,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  max_member1 (const ::std::string& s,
+               const ::xercesc::DOMElement* e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  max_member1 (const max_member1& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual max_member1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  virtual 
+  ~max_member1 ();
+};
+
+class marking: public ::xml_schema::type
+{
+  public:
+  // side
+  //
+  typedef ::parkingSpacemarkingSide side_type;
+  typedef ::xsd::cxx::tree::optional< side_type > side_optional;
+  typedef ::xsd::cxx::tree::traits< side_type, char > side_traits;
+
+  const side_optional&
+  side () const;
+
+  side_optional&
+  side ();
+
+  void
+  side (const side_type& x);
+
+  void
+  side (const side_optional& x);
+
+  void
+  side (::std::unique_ptr< side_type > p);
+
+  // type
+  //
+  typedef ::roadmarkType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // color
+  //
+  typedef ::color color_type;
+  typedef ::xsd::cxx::tree::optional< color_type > color_optional;
+  typedef ::xsd::cxx::tree::traits< color_type, char > color_traits;
+
+  const color_optional&
+  color () const;
+
+  color_optional&
+  color ();
+
+  void
+  color (const color_type& x);
+
+  void
+  color (const color_optional& x);
+
+  void
+  color (::std::unique_ptr< color_type > p);
+
+  // Constructors.
+  //
+  marking ();
+
+  marking (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  marking (const marking& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual marking*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  marking&
+  operator= (const marking& x);
+
+  virtual 
+  ~marking ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  side_optional side_;
+  type_optional type_;
+  width_optional width_;
+  color_optional color_;
+};
+
+class lane_link: public ::xml_schema::type
+{
+  public:
+  // predecessor
+  //
+  typedef ::predecessor predecessor_type;
+  typedef ::xsd::cxx::tree::optional< predecessor_type > predecessor_optional;
+  typedef ::xsd::cxx::tree::traits< predecessor_type, char > predecessor_traits;
+
+  const predecessor_optional&
+  predecessor () const;
+
+  predecessor_optional&
+  predecessor ();
+
+  void
+  predecessor (const predecessor_type& x);
+
+  void
+  predecessor (const predecessor_optional& x);
+
+  void
+  predecessor (::std::unique_ptr< predecessor_type > p);
+
+  // successor
+  //
+  typedef ::successor successor_type;
+  typedef ::xsd::cxx::tree::optional< successor_type > successor_optional;
+  typedef ::xsd::cxx::tree::traits< successor_type, char > successor_traits;
+
+  const successor_optional&
+  successor () const;
+
+  successor_optional&
+  successor ();
+
+  void
+  successor (const successor_type& x);
+
+  void
+  successor (const successor_optional& x);
+
+  void
+  successor (::std::unique_ptr< successor_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  lane_link ();
+
+  lane_link (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  lane_link (const lane_link& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual lane_link*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  lane_link&
+  operator= (const lane_link& x);
+
+  virtual 
+  ~lane_link ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  predecessor_optional predecessor_;
+  successor_optional successor_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class width: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  width ();
+
+  width (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  width (const width& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual width*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  width&
+  operator= (const width& x);
+
+  virtual 
+  ~width ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class border: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  border ();
+
+  border (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  border (const border& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual border*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  border&
+  operator= (const border& x);
+
+  virtual 
+  ~border ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class roadMark: public ::xml_schema::type
+{
+  public:
+  // type
+  //
+  typedef ::type type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // type
+  //
+  typedef ::roadmarkType type1_type;
+  typedef ::xsd::cxx::tree::optional< type1_type > type1_optional;
+  typedef ::xsd::cxx::tree::traits< type1_type, char > type1_traits;
+
+  const type1_optional&
+  type1 () const;
+
+  type1_optional&
+  type1 ();
+
+  void
+  type1 (const type1_type& x);
+
+  void
+  type1 (const type1_optional& x);
+
+  void
+  type1 (::std::unique_ptr< type1_type > p);
+
+  // weight
+  //
+  typedef ::weight weight_type;
+  typedef ::xsd::cxx::tree::optional< weight_type > weight_optional;
+  typedef ::xsd::cxx::tree::traits< weight_type, char > weight_traits;
+
+  const weight_optional&
+  weight () const;
+
+  weight_optional&
+  weight ();
+
+  void
+  weight (const weight_type& x);
+
+  void
+  weight (const weight_optional& x);
+
+  void
+  weight (::std::unique_ptr< weight_type > p);
+
+  // color
+  //
+  typedef ::color color_type;
+  typedef ::xsd::cxx::tree::optional< color_type > color_optional;
+  typedef ::xsd::cxx::tree::traits< color_type, char > color_traits;
+
+  const color_optional&
+  color () const;
+
+  color_optional&
+  color ();
+
+  void
+  color (const color_type& x);
+
+  void
+  color (const color_optional& x);
+
+  void
+  color (::std::unique_ptr< color_type > p);
+
+  // material
+  //
+  typedef ::xml_schema::string material_type;
+  typedef ::xsd::cxx::tree::optional< material_type > material_optional;
+  typedef ::xsd::cxx::tree::traits< material_type, char > material_traits;
+
+  const material_optional&
+  material () const;
+
+  material_optional&
+  material ();
+
+  void
+  material (const material_type& x);
+
+  void
+  material (const material_optional& x);
+
+  void
+  material (::std::unique_ptr< material_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // laneChange
+  //
+  typedef ::laneChange laneChange_type;
+  typedef ::xsd::cxx::tree::optional< laneChange_type > laneChange_optional;
+  typedef ::xsd::cxx::tree::traits< laneChange_type, char > laneChange_traits;
+
+  const laneChange_optional&
+  laneChange () const;
+
+  laneChange_optional&
+  laneChange ();
+
+  void
+  laneChange (const laneChange_type& x);
+
+  void
+  laneChange (const laneChange_optional& x);
+
+  void
+  laneChange (::std::unique_ptr< laneChange_type > p);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // Constructors.
+  //
+  roadMark ();
+
+  roadMark (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  roadMark (const roadMark& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual roadMark*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  roadMark&
+  operator= (const roadMark& x);
+
+  virtual 
+  ~roadMark ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  type_optional type_;
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  type1_optional type1_;
+  weight_optional weight_;
+  color_optional color_;
+  material_optional material_;
+  width_optional width_;
+  laneChange_optional laneChange_;
+  height_optional height_;
+};
+
+class material: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // surface
+  //
+  typedef ::xml_schema::string surface_type;
+  typedef ::xsd::cxx::tree::optional< surface_type > surface_optional;
+  typedef ::xsd::cxx::tree::traits< surface_type, char > surface_traits;
+
+  const surface_optional&
+  surface () const;
+
+  surface_optional&
+  surface ();
+
+  void
+  surface (const surface_type& x);
+
+  void
+  surface (const surface_optional& x);
+
+  void
+  surface (::std::unique_ptr< surface_type > p);
+
+  // friction
+  //
+  typedef ::xml_schema::double_ friction_type;
+  typedef ::xsd::cxx::tree::optional< friction_type > friction_optional;
+  typedef ::xsd::cxx::tree::traits< friction_type, char, ::xsd::cxx::tree::schema_type::double_ > friction_traits;
+
+  const friction_optional&
+  friction () const;
+
+  friction_optional&
+  friction ();
+
+  void
+  friction (const friction_type& x);
+
+  void
+  friction (const friction_optional& x);
+
+  // roughness
+  //
+  typedef ::xml_schema::double_ roughness_type;
+  typedef ::xsd::cxx::tree::optional< roughness_type > roughness_optional;
+  typedef ::xsd::cxx::tree::traits< roughness_type, char, ::xsd::cxx::tree::schema_type::double_ > roughness_traits;
+
+  const roughness_optional&
+  roughness () const;
+
+  roughness_optional&
+  roughness ();
+
+  void
+  roughness (const roughness_type& x);
+
+  void
+  roughness (const roughness_optional& x);
+
+  // Constructors.
+  //
+  material ();
+
+  material (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  material (const material& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual material*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  material&
+  operator= (const material& x);
+
+  virtual 
+  ~material ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  surface_optional surface_;
+  friction_optional friction_;
+  roughness_optional roughness_;
+};
+
+class visibility: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // forward
+  //
+  typedef ::xml_schema::double_ forward_type;
+  typedef ::xsd::cxx::tree::optional< forward_type > forward_optional;
+  typedef ::xsd::cxx::tree::traits< forward_type, char, ::xsd::cxx::tree::schema_type::double_ > forward_traits;
+
+  const forward_optional&
+  forward () const;
+
+  forward_optional&
+  forward ();
+
+  void
+  forward (const forward_type& x);
+
+  void
+  forward (const forward_optional& x);
+
+  // back
+  //
+  typedef ::xml_schema::double_ back_type;
+  typedef ::xsd::cxx::tree::optional< back_type > back_optional;
+  typedef ::xsd::cxx::tree::traits< back_type, char, ::xsd::cxx::tree::schema_type::double_ > back_traits;
+
+  const back_optional&
+  back () const;
+
+  back_optional&
+  back ();
+
+  void
+  back (const back_type& x);
+
+  void
+  back (const back_optional& x);
+
+  // left
+  //
+  typedef ::xml_schema::double_ left_type;
+  typedef ::xsd::cxx::tree::optional< left_type > left_optional;
+  typedef ::xsd::cxx::tree::traits< left_type, char, ::xsd::cxx::tree::schema_type::double_ > left_traits;
+
+  const left_optional&
+  left () const;
+
+  left_optional&
+  left ();
+
+  void
+  left (const left_type& x);
+
+  void
+  left (const left_optional& x);
+
+  // right
+  //
+  typedef ::xml_schema::double_ right_type;
+  typedef ::xsd::cxx::tree::optional< right_type > right_optional;
+  typedef ::xsd::cxx::tree::traits< right_type, char, ::xsd::cxx::tree::schema_type::double_ > right_traits;
+
+  const right_optional&
+  right () const;
+
+  right_optional&
+  right ();
+
+  void
+  right (const right_type& x);
+
+  void
+  right (const right_optional& x);
+
+  // Constructors.
+  //
+  visibility ();
+
+  visibility (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  visibility (const visibility& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual visibility*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  visibility&
+  operator= (const visibility& x);
+
+  virtual 
+  ~visibility ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  forward_optional forward_;
+  back_optional back_;
+  left_optional left_;
+  right_optional right_;
+};
+
+class speed: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // max
+  //
+  typedef ::xml_schema::double_ max_type;
+  typedef ::xsd::cxx::tree::optional< max_type > max_optional;
+  typedef ::xsd::cxx::tree::traits< max_type, char, ::xsd::cxx::tree::schema_type::double_ > max_traits;
+
+  const max_optional&
+  max () const;
+
+  max_optional&
+  max ();
+
+  void
+  max (const max_type& x);
+
+  void
+  max (const max_optional& x);
+
+  // unit
+  //
+  typedef ::unit unit_type;
+  typedef ::xsd::cxx::tree::optional< unit_type > unit_optional;
+  typedef ::xsd::cxx::tree::traits< unit_type, char > unit_traits;
+
+  const unit_optional&
+  unit () const;
+
+  unit_optional&
+  unit ();
+
+  void
+  unit (const unit_type& x);
+
+  void
+  unit (const unit_optional& x);
+
+  void
+  unit (::std::unique_ptr< unit_type > p);
+
+  // Constructors.
+  //
+  speed ();
+
+  speed (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  speed (const speed& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual speed*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  speed&
+  operator= (const speed& x);
+
+  virtual 
+  ~speed ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  max_optional max_;
+  unit_optional unit_;
+};
+
+class access1: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // restriction
+  //
+  typedef ::restriction restriction_type;
+  typedef ::xsd::cxx::tree::optional< restriction_type > restriction_optional;
+  typedef ::xsd::cxx::tree::traits< restriction_type, char > restriction_traits;
+
+  const restriction_optional&
+  restriction () const;
+
+  restriction_optional&
+  restriction ();
+
+  void
+  restriction (const restriction_type& x);
+
+  void
+  restriction (const restriction_optional& x);
+
+  void
+  restriction (::std::unique_ptr< restriction_type > p);
+
+  // Constructors.
+  //
+  access1 ();
+
+  access1 (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  access1 (const access1& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual access1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  access1&
+  operator= (const access1& x);
+
+  virtual 
+  ~access1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  restriction_optional restriction_;
+};
+
+class height: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // inner
+  //
+  typedef ::xml_schema::double_ inner_type;
+  typedef ::xsd::cxx::tree::optional< inner_type > inner_optional;
+  typedef ::xsd::cxx::tree::traits< inner_type, char, ::xsd::cxx::tree::schema_type::double_ > inner_traits;
+
+  const inner_optional&
+  inner () const;
+
+  inner_optional&
+  inner ();
+
+  void
+  inner (const inner_type& x);
+
+  void
+  inner (const inner_optional& x);
+
+  // outer
+  //
+  typedef ::xml_schema::double_ outer_type;
+  typedef ::xsd::cxx::tree::optional< outer_type > outer_optional;
+  typedef ::xsd::cxx::tree::traits< outer_type, char, ::xsd::cxx::tree::schema_type::double_ > outer_traits;
+
+  const outer_optional&
+  outer () const;
+
+  outer_optional&
+  outer ();
+
+  void
+  outer (const outer_type& x);
+
+  void
+  outer (const outer_optional& x);
+
+  // Constructors.
+  //
+  height ();
+
+  height (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  height (const height& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual height*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  height&
+  operator= (const height& x);
+
+  virtual 
+  ~height ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  inner_optional inner_;
+  outer_optional outer_;
+};
+
+class rule1: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // value
+  //
+  typedef ::xml_schema::string value_type;
+  typedef ::xsd::cxx::tree::optional< value_type > value_optional;
+  typedef ::xsd::cxx::tree::traits< value_type, char > value_traits;
+
+  const value_optional&
+  value () const;
+
+  value_optional&
+  value ();
+
+  void
+  value (const value_type& x);
+
+  void
+  value (const value_optional& x);
+
+  void
+  value (::std::unique_ptr< value_type > p);
+
+  // Constructors.
+  //
+  rule1 ();
+
+  rule1 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  rule1 (const rule1& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual rule1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  rule1&
+  operator= (const rule1& x);
+
+  virtual 
+  ~rule1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  value_optional value_;
+};
+
+class link1: public ::xml_schema::type
+{
+  public:
+  // predecessor
+  //
+  typedef ::predecessor predecessor_type;
+  typedef ::xsd::cxx::tree::optional< predecessor_type > predecessor_optional;
+  typedef ::xsd::cxx::tree::traits< predecessor_type, char > predecessor_traits;
+
+  const predecessor_optional&
+  predecessor () const;
+
+  predecessor_optional&
+  predecessor ();
+
+  void
+  predecessor (const predecessor_type& x);
+
+  void
+  predecessor (const predecessor_optional& x);
+
+  void
+  predecessor (::std::unique_ptr< predecessor_type > p);
+
+  // successor
+  //
+  typedef ::successor successor_type;
+  typedef ::xsd::cxx::tree::optional< successor_type > successor_optional;
+  typedef ::xsd::cxx::tree::traits< successor_type, char > successor_traits;
+
+  const successor_optional&
+  successor () const;
+
+  successor_optional&
+  successor ();
+
+  void
+  successor (const successor_type& x);
+
+  void
+  successor (const successor_optional& x);
+
+  void
+  successor (::std::unique_ptr< successor_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  link1 ();
+
+  link1 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  link1 (const link1& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual link1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  link1&
+  operator= (const link1& x);
+
+  virtual 
+  ~link1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  predecessor_optional predecessor_;
+  successor_optional successor_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class roadMark1: public ::xml_schema::type
+{
+  public:
+  // type
+  //
+  typedef ::type1 type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // type
+  //
+  typedef ::roadmarkType type1_type;
+  typedef ::xsd::cxx::tree::optional< type1_type > type1_optional;
+  typedef ::xsd::cxx::tree::traits< type1_type, char > type1_traits;
+
+  const type1_optional&
+  type1 () const;
+
+  type1_optional&
+  type1 ();
+
+  void
+  type1 (const type1_type& x);
+
+  void
+  type1 (const type1_optional& x);
+
+  void
+  type1 (::std::unique_ptr< type1_type > p);
+
+  // weight
+  //
+  typedef ::weight weight_type;
+  typedef ::xsd::cxx::tree::optional< weight_type > weight_optional;
+  typedef ::xsd::cxx::tree::traits< weight_type, char > weight_traits;
+
+  const weight_optional&
+  weight () const;
+
+  weight_optional&
+  weight ();
+
+  void
+  weight (const weight_type& x);
+
+  void
+  weight (const weight_optional& x);
+
+  void
+  weight (::std::unique_ptr< weight_type > p);
+
+  // color
+  //
+  typedef ::color color_type;
+  typedef ::xsd::cxx::tree::optional< color_type > color_optional;
+  typedef ::xsd::cxx::tree::traits< color_type, char > color_traits;
+
+  const color_optional&
+  color () const;
+
+  color_optional&
+  color ();
+
+  void
+  color (const color_type& x);
+
+  void
+  color (const color_optional& x);
+
+  void
+  color (::std::unique_ptr< color_type > p);
+
+  // material
+  //
+  typedef ::xml_schema::string material_type;
+  typedef ::xsd::cxx::tree::optional< material_type > material_optional;
+  typedef ::xsd::cxx::tree::traits< material_type, char > material_traits;
+
+  const material_optional&
+  material () const;
+
+  material_optional&
+  material ();
+
+  void
+  material (const material_type& x);
+
+  void
+  material (const material_optional& x);
+
+  void
+  material (::std::unique_ptr< material_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // laneChange
+  //
+  typedef ::laneChange laneChange_type;
+  typedef ::xsd::cxx::tree::optional< laneChange_type > laneChange_optional;
+  typedef ::xsd::cxx::tree::traits< laneChange_type, char > laneChange_traits;
+
+  const laneChange_optional&
+  laneChange () const;
+
+  laneChange_optional&
+  laneChange ();
+
+  void
+  laneChange (const laneChange_type& x);
+
+  void
+  laneChange (const laneChange_optional& x);
+
+  void
+  laneChange (::std::unique_ptr< laneChange_type > p);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // Constructors.
+  //
+  roadMark1 ();
+
+  roadMark1 (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  roadMark1 (const roadMark1& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual roadMark1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  roadMark1&
+  operator= (const roadMark1& x);
+
+  virtual 
+  ~roadMark1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  type_optional type_;
+  userData_sequence userData_;
+  include_sequence include_;
+  sOffset_optional sOffset_;
+  type1_optional type1_;
+  weight_optional weight_;
+  color_optional color_;
+  material_optional material_;
+  width_optional width_;
+  laneChange_optional laneChange_;
+  height_optional height_;
+};
+
+class header: public ::xml_schema::type
+{
+  public:
+  // geoReference
+  //
+  typedef ::xml_schema::string geoReference_type;
+  typedef ::xsd::cxx::tree::optional< geoReference_type > geoReference_optional;
+  typedef ::xsd::cxx::tree::traits< geoReference_type, char > geoReference_traits;
+
+  const geoReference_optional&
+  geoReference () const;
+
+  geoReference_optional&
+  geoReference ();
+
+  void
+  geoReference (const geoReference_type& x);
+
+  void
+  geoReference (const geoReference_optional& x);
+
+  void
+  geoReference (::std::unique_ptr< geoReference_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // revMajor
+  //
+  typedef ::xml_schema::unsigned_short revMajor_type;
+  typedef ::xsd::cxx::tree::optional< revMajor_type > revMajor_optional;
+  typedef ::xsd::cxx::tree::traits< revMajor_type, char > revMajor_traits;
+
+  const revMajor_optional&
+  revMajor () const;
+
+  revMajor_optional&
+  revMajor ();
+
+  void
+  revMajor (const revMajor_type& x);
+
+  void
+  revMajor (const revMajor_optional& x);
+
+  // revMinor
+  //
+  typedef ::xml_schema::unsigned_short revMinor_type;
+  typedef ::xsd::cxx::tree::optional< revMinor_type > revMinor_optional;
+  typedef ::xsd::cxx::tree::traits< revMinor_type, char > revMinor_traits;
+
+  const revMinor_optional&
+  revMinor () const;
+
+  revMinor_optional&
+  revMinor ();
+
+  void
+  revMinor (const revMinor_type& x);
+
+  void
+  revMinor (const revMinor_optional& x);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // version
+  //
+  typedef ::xml_schema::float_ version_type;
+  typedef ::xsd::cxx::tree::optional< version_type > version_optional;
+  typedef ::xsd::cxx::tree::traits< version_type, char > version_traits;
+
+  const version_optional&
+  version () const;
+
+  version_optional&
+  version ();
+
+  void
+  version (const version_type& x);
+
+  void
+  version (const version_optional& x);
+
+  // date
+  //
+  typedef ::xml_schema::string date_type;
+  typedef ::xsd::cxx::tree::optional< date_type > date_optional;
+  typedef ::xsd::cxx::tree::traits< date_type, char > date_traits;
+
+  const date_optional&
+  date () const;
+
+  date_optional&
+  date ();
+
+  void
+  date (const date_type& x);
+
+  void
+  date (const date_optional& x);
+
+  void
+  date (::std::unique_ptr< date_type > p);
+
+  // north
+  //
+  typedef ::xml_schema::double_ north_type;
+  typedef ::xsd::cxx::tree::optional< north_type > north_optional;
+  typedef ::xsd::cxx::tree::traits< north_type, char, ::xsd::cxx::tree::schema_type::double_ > north_traits;
+
+  const north_optional&
+  north () const;
+
+  north_optional&
+  north ();
+
+  void
+  north (const north_type& x);
+
+  void
+  north (const north_optional& x);
+
+  // south
+  //
+  typedef ::xml_schema::double_ south_type;
+  typedef ::xsd::cxx::tree::optional< south_type > south_optional;
+  typedef ::xsd::cxx::tree::traits< south_type, char, ::xsd::cxx::tree::schema_type::double_ > south_traits;
+
+  const south_optional&
+  south () const;
+
+  south_optional&
+  south ();
+
+  void
+  south (const south_type& x);
+
+  void
+  south (const south_optional& x);
+
+  // east
+  //
+  typedef ::xml_schema::double_ east_type;
+  typedef ::xsd::cxx::tree::optional< east_type > east_optional;
+  typedef ::xsd::cxx::tree::traits< east_type, char, ::xsd::cxx::tree::schema_type::double_ > east_traits;
+
+  const east_optional&
+  east () const;
+
+  east_optional&
+  east ();
+
+  void
+  east (const east_type& x);
+
+  void
+  east (const east_optional& x);
+
+  // west
+  //
+  typedef ::xml_schema::double_ west_type;
+  typedef ::xsd::cxx::tree::optional< west_type > west_optional;
+  typedef ::xsd::cxx::tree::traits< west_type, char, ::xsd::cxx::tree::schema_type::double_ > west_traits;
+
+  const west_optional&
+  west () const;
+
+  west_optional&
+  west ();
+
+  void
+  west (const west_type& x);
+
+  void
+  west (const west_optional& x);
+
+  // vendor
+  //
+  typedef ::xml_schema::string vendor_type;
+  typedef ::xsd::cxx::tree::optional< vendor_type > vendor_optional;
+  typedef ::xsd::cxx::tree::traits< vendor_type, char > vendor_traits;
+
+  const vendor_optional&
+  vendor () const;
+
+  vendor_optional&
+  vendor ();
+
+  void
+  vendor (const vendor_type& x);
+
+  void
+  vendor (const vendor_optional& x);
+
+  void
+  vendor (::std::unique_ptr< vendor_type > p);
+
+  // Constructors.
+  //
+  header ();
+
+  header (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  header (const header& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual header*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  header&
+  operator= (const header& x);
+
+  virtual 
+  ~header ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  geoReference_optional geoReference_;
+  userData_sequence userData_;
+  include_sequence include_;
+  revMajor_optional revMajor_;
+  revMinor_optional revMinor_;
+  name_optional name_;
+  version_optional version_;
+  date_optional date_;
+  north_optional north_;
+  south_optional south_;
+  east_optional east_;
+  west_optional west_;
+  vendor_optional vendor_;
+};
+
+class road: public ::xml_schema::type
+{
+  public:
+  // link
+  //
+  typedef ::link2 link_type;
+  typedef ::xsd::cxx::tree::optional< link_type > link_optional;
+  typedef ::xsd::cxx::tree::traits< link_type, char > link_traits;
+
+  const link_optional&
+  lane_link () const;
+
+  link_optional&
+  lane_link ();
+
+  void
+  lane_link (const link_type& x);
+
+  void
+  lane_link (const link_optional& x);
+
+  void
+  lane_link (::std::unique_ptr< link_type > p);
+
+  // type
+  //
+  typedef ::type2 type_type;
+  typedef ::xsd::cxx::tree::sequence< type_type > type_sequence;
+  typedef type_sequence::iterator type_iterator;
+  typedef type_sequence::const_iterator type_const_iterator;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_sequence&
+  type () const;
+
+  type_sequence&
+  type ();
+
+  void
+  type (const type_sequence& s);
+
+  // planView
+  //
+  typedef ::planView planView_type;
+  typedef ::xsd::cxx::tree::traits< planView_type, char > planView_traits;
+
+  const planView_type&
+  planView () const;
+
+  planView_type&
+  planView ();
+
+  void
+  planView (const planView_type& x);
+
+  void
+  planView (::std::unique_ptr< planView_type > p);
+
+  // elevationProfile
+  //
+  typedef ::elevationProfile elevationProfile_type;
+  typedef ::xsd::cxx::tree::optional< elevationProfile_type > elevationProfile_optional;
+  typedef ::xsd::cxx::tree::traits< elevationProfile_type, char > elevationProfile_traits;
+
+  const elevationProfile_optional&
+  elevationProfile () const;
+
+  elevationProfile_optional&
+  elevationProfile ();
+
+  void
+  elevationProfile (const elevationProfile_type& x);
+
+  void
+  elevationProfile (const elevationProfile_optional& x);
+
+  void
+  elevationProfile (::std::unique_ptr< elevationProfile_type > p);
+
+  // lateralProfile
+  //
+  typedef ::lateralProfile lateralProfile_type;
+  typedef ::xsd::cxx::tree::optional< lateralProfile_type > lateralProfile_optional;
+  typedef ::xsd::cxx::tree::traits< lateralProfile_type, char > lateralProfile_traits;
+
+  const lateralProfile_optional&
+  lateralProfile () const;
+
+  lateralProfile_optional&
+  lateralProfile ();
+
+  void
+  lateralProfile (const lateralProfile_type& x);
+
+  void
+  lateralProfile (const lateralProfile_optional& x);
+
+  void
+  lateralProfile (::std::unique_ptr< lateralProfile_type > p);
+
+  // lanes
+  //
+  typedef ::lanes lanes_type;
+  typedef ::xsd::cxx::tree::traits< lanes_type, char > lanes_traits;
+
+  const lanes_type&
+  lanes () const;
+
+  lanes_type&
+  lanes ();
+
+  void
+  lanes (const lanes_type& x);
+
+  void
+  lanes (::std::unique_ptr< lanes_type > p);
+
+  // objects
+  //
+  typedef ::objects objects_type;
+  typedef ::xsd::cxx::tree::optional< objects_type > objects_optional;
+  typedef ::xsd::cxx::tree::traits< objects_type, char > objects_traits;
+
+  const objects_optional&
+  objects () const;
+
+  objects_optional&
+  objects ();
+
+  void
+  objects (const objects_type& x);
+
+  void
+  objects (const objects_optional& x);
+
+  void
+  objects (::std::unique_ptr< objects_type > p);
+
+  // signals
+  //
+  typedef ::signals signals_type;
+  typedef ::xsd::cxx::tree::optional< signals_type > signals_optional;
+  typedef ::xsd::cxx::tree::traits< signals_type, char > signals_traits;
+
+  const signals_optional&
+  signals () const;
+
+  signals_optional&
+  signals ();
+
+  void
+  signals (const signals_type& x);
+
+  void
+  signals (const signals_optional& x);
+
+  void
+  signals (::std::unique_ptr< signals_type > p);
+
+  // surface
+  //
+  typedef ::surface surface_type;
+  typedef ::xsd::cxx::tree::optional< surface_type > surface_optional;
+  typedef ::xsd::cxx::tree::traits< surface_type, char > surface_traits;
+
+  const surface_optional&
+  surface () const;
+
+  surface_optional&
+  surface ();
+
+  void
+  surface (const surface_type& x);
+
+  void
+  surface (const surface_optional& x);
+
+  void
+  surface (::std::unique_ptr< surface_type > p);
+
+  // railroad
+  //
+  typedef ::railroad railroad_type;
+  typedef ::xsd::cxx::tree::optional< railroad_type > railroad_optional;
+  typedef ::xsd::cxx::tree::traits< railroad_type, char > railroad_traits;
+
+  const railroad_optional&
+  railroad () const;
+
+  railroad_optional&
+  railroad ();
+
+  void
+  railroad (const railroad_type& x);
+
+  void
+  railroad (const railroad_optional& x);
+
+  void
+  railroad (::std::unique_ptr< railroad_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // junction
+  //
+  typedef ::xml_schema::string junction_type;
+  typedef ::xsd::cxx::tree::optional< junction_type > junction_optional;
+  typedef ::xsd::cxx::tree::traits< junction_type, char > junction_traits;
+
+  const junction_optional&
+  junction () const;
+
+  junction_optional&
+  junction ();
+
+  void
+  junction (const junction_type& x);
+
+  void
+  junction (const junction_optional& x);
+
+  void
+  junction (::std::unique_ptr< junction_type > p);
+
+  // Constructors.
+  //
+  road (const planView_type&,
+        const lanes_type&);
+
+  road (::std::unique_ptr< planView_type >,
+        ::std::unique_ptr< lanes_type >);
+
+  road (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  road (const road& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual road*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  road&
+  operator= (const road& x);
+
+  virtual 
+  ~road ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  link_optional lane_link_;
+  type_sequence type_;
+  ::xsd::cxx::tree::one< planView_type > planView_;
+  elevationProfile_optional elevationProfile_;
+  lateralProfile_optional lateralProfile_;
+  ::xsd::cxx::tree::one< lanes_type > lanes_;
+  objects_optional objects_;
+  signals_optional signals_;
+  surface_optional surface_;
+  railroad_optional railroad_;
+  userData_sequence userData_;
+  include_sequence include_;
+  name_optional name_;
+  length_optional length_;
+  id_optional id_;
+  junction_optional junction_;
+};
+
+class controller: public ::xml_schema::type
+{
+  public:
+  // control
+  //
+  typedef ::control control_type;
+  typedef ::xsd::cxx::tree::sequence< control_type > control_sequence;
+  typedef control_sequence::iterator control_iterator;
+  typedef control_sequence::const_iterator control_const_iterator;
+  typedef ::xsd::cxx::tree::traits< control_type, char > control_traits;
+
+  const control_sequence&
+  control () const;
+
+  control_sequence&
+  control ();
+
+  void
+  control (const control_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // sequence
+  //
+  typedef ::xml_schema::int_ sequence_type;
+  typedef ::xsd::cxx::tree::optional< sequence_type > sequence_optional;
+  typedef ::xsd::cxx::tree::traits< sequence_type, char > sequence_traits;
+
+  const sequence_optional&
+  sequence () const;
+
+  sequence_optional&
+  sequence ();
+
+  void
+  sequence (const sequence_type& x);
+
+  void
+  sequence (const sequence_optional& x);
+
+  // Constructors.
+  //
+  controller ();
+
+  controller (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  controller (const controller& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual controller*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  controller&
+  operator= (const controller& x);
+
+  virtual 
+  ~controller ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  control_sequence control_;
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  name_optional name_;
+  sequence_optional sequence_;
+};
+
+class junction: public ::xml_schema::type
+{
+  public:
+  // connection
+  //
+  typedef ::connection connection_type;
+  typedef ::xsd::cxx::tree::sequence< connection_type > connection_sequence;
+  typedef connection_sequence::iterator connection_iterator;
+  typedef connection_sequence::const_iterator connection_const_iterator;
+  typedef ::xsd::cxx::tree::traits< connection_type, char > connection_traits;
+
+  const connection_sequence&
+  connection () const;
+
+  connection_sequence&
+  connection ();
+
+  void
+  connection (const connection_sequence& s);
+
+  // priority
+  //
+  typedef ::priority priority_type;
+  typedef ::xsd::cxx::tree::sequence< priority_type > priority_sequence;
+  typedef priority_sequence::iterator priority_iterator;
+  typedef priority_sequence::const_iterator priority_const_iterator;
+  typedef ::xsd::cxx::tree::traits< priority_type, char > priority_traits;
+
+  const priority_sequence&
+  priority () const;
+
+  priority_sequence&
+  priority ();
+
+  void
+  priority (const priority_sequence& s);
+
+  // controller
+  //
+  typedef ::controller1 controller_type;
+  typedef ::xsd::cxx::tree::sequence< controller_type > controller_sequence;
+  typedef controller_sequence::iterator controller_iterator;
+  typedef controller_sequence::const_iterator controller_const_iterator;
+  typedef ::xsd::cxx::tree::traits< controller_type, char > controller_traits;
+
+  const controller_sequence&
+  controller () const;
+
+  controller_sequence&
+  controller ();
+
+  void
+  controller (const controller_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // Constructors.
+  //
+  junction ();
+
+  junction (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  junction (const junction& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual junction*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  junction&
+  operator= (const junction& x);
+
+  virtual 
+  ~junction ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  connection_sequence connection_;
+  priority_sequence priority_;
+  controller_sequence controller_;
+  userData_sequence userData_;
+  include_sequence include_;
+  name_optional name_;
+  id_optional id_;
+};
+
+class junctionGroup: public ::xml_schema::type
+{
+  public:
+  // junctionReference
+  //
+  typedef ::junctionReference junctionReference_type;
+  typedef ::xsd::cxx::tree::sequence< junctionReference_type > junctionReference_sequence;
+  typedef junctionReference_sequence::iterator junctionReference_iterator;
+  typedef junctionReference_sequence::const_iterator junctionReference_const_iterator;
+  typedef ::xsd::cxx::tree::traits< junctionReference_type, char > junctionReference_traits;
+
+  const junctionReference_sequence&
+  junctionReference () const;
+
+  junctionReference_sequence&
+  junctionReference ();
+
+  void
+  junctionReference (const junctionReference_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::junctionGroupType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  junctionGroup ();
+
+  junctionGroup (const ::xercesc::DOMElement& e,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  junctionGroup (const junctionGroup& x,
+                 ::xml_schema::flags f = 0,
+                 ::xml_schema::container* c = 0);
+
+  virtual junctionGroup*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  junctionGroup&
+  operator= (const junctionGroup& x);
+
+  virtual 
+  ~junctionGroup ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  junctionReference_sequence junctionReference_;
+  userData_sequence userData_;
+  include_sequence include_;
+  name_optional name_;
+  id_optional id_;
+  type_optional type_;
+};
+
+class station: public ::xml_schema::type
+{
+  public:
+  // platform
+  //
+  typedef ::platform platform_type;
+  typedef ::xsd::cxx::tree::sequence< platform_type > platform_sequence;
+  typedef platform_sequence::iterator platform_iterator;
+  typedef platform_sequence::const_iterator platform_const_iterator;
+  typedef ::xsd::cxx::tree::traits< platform_type, char > platform_traits;
+
+  const platform_sequence&
+  platform () const;
+
+  platform_sequence&
+  platform ();
+
+  void
+  platform (const platform_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::stationType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  station ();
+
+  station (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  station (const station& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual station*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  station&
+  operator= (const station& x);
+
+  virtual 
+  ~station ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  platform_sequence platform_;
+  userData_sequence userData_;
+  include_sequence include_;
+  name_optional name_;
+  id_optional id_;
+  type_optional type_;
+};
+
+class predecessor: public ::xml_schema::type
+{
+  public:
+  // id
+  //
+  typedef ::xml_schema::int_ id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  // Constructors.
+  //
+  predecessor ();
+
+  predecessor (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  predecessor (const predecessor& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual predecessor*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  predecessor&
+  operator= (const predecessor& x);
+
+  virtual 
+  ~predecessor ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  id_optional id_;
+};
+
+class successor: public ::xml_schema::type
+{
+  public:
+  // id
+  //
+  typedef ::xml_schema::int_ id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  // Constructors.
+  //
+  successor ();
+
+  successor (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  successor (const successor& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual successor*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  successor&
+  operator= (const successor& x);
+
+  virtual 
+  ~successor ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  id_optional id_;
+};
+
+class type: public ::xml_schema::type
+{
+  public:
+  // line
+  //
+  typedef ::line line_type;
+  typedef ::xsd::cxx::tree::sequence< line_type > line_sequence;
+  typedef line_sequence::iterator line_iterator;
+  typedef line_sequence::const_iterator line_const_iterator;
+  typedef ::xsd::cxx::tree::traits< line_type, char > line_traits;
+
+  const line_sequence&
+  line () const;
+
+  line_sequence&
+  line ();
+
+  void
+  line (const line_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // Constructors.
+  //
+  type ();
+
+  type (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  type (const type& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual type*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  type&
+  operator= (const type& x);
+
+  virtual 
+  ~type ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  line_sequence line_;
+  name_optional name_;
+  width_optional width_;
+};
+
+class type1: public ::xml_schema::type
+{
+  public:
+  // line
+  //
+  typedef ::line line_type;
+  typedef ::xsd::cxx::tree::sequence< line_type > line_sequence;
+  typedef line_sequence::iterator line_iterator;
+  typedef line_sequence::const_iterator line_const_iterator;
+  typedef ::xsd::cxx::tree::traits< line_type, char > line_traits;
+
+  const line_sequence&
+  line () const;
+
+  line_sequence&
+  line ();
+
+  void
+  line (const line_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // Constructors.
+  //
+  type1 ();
+
+  type1 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  type1 (const type1& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual type1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  type1&
+  operator= (const type1& x);
+
+  virtual 
+  ~type1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  line_sequence line_;
+  name_optional name_;
+  width_optional width_;
+};
+
+class link2: public ::xml_schema::type
+{
+  public:
+  // predecessor
+  //
+  typedef ::predecessor1 predecessor_type;
+  typedef ::xsd::cxx::tree::optional< predecessor_type > predecessor_optional;
+  typedef ::xsd::cxx::tree::traits< predecessor_type, char > predecessor_traits;
+
+  const predecessor_optional&
+  predecessor () const;
+
+  predecessor_optional&
+  predecessor ();
+
+  void
+  predecessor (const predecessor_type& x);
+
+  void
+  predecessor (const predecessor_optional& x);
+
+  void
+  predecessor (::std::unique_ptr< predecessor_type > p);
+
+  // successor
+  //
+  typedef ::successor1 successor_type;
+  typedef ::xsd::cxx::tree::optional< successor_type > successor_optional;
+  typedef ::xsd::cxx::tree::traits< successor_type, char > successor_traits;
+
+  const successor_optional&
+  successor () const;
+
+  successor_optional&
+  successor ();
+
+  void
+  successor (const successor_type& x);
+
+  void
+  successor (const successor_optional& x);
+
+  void
+  successor (::std::unique_ptr< successor_type > p);
+
+  // neighbor
+  //
+  typedef ::neighbor neighbor_type;
+  typedef ::xsd::cxx::tree::sequence< neighbor_type > neighbor_sequence;
+  typedef neighbor_sequence::iterator neighbor_iterator;
+  typedef neighbor_sequence::const_iterator neighbor_const_iterator;
+  typedef ::xsd::cxx::tree::traits< neighbor_type, char > neighbor_traits;
+
+  const neighbor_sequence&
+  neighbor () const;
+
+  neighbor_sequence&
+  neighbor ();
+
+  void
+  neighbor (const neighbor_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  link2 ();
+
+  link2 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  link2 (const link2& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual link2*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  link2&
+  operator= (const link2& x);
+
+  virtual 
+  ~link2 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  predecessor_optional predecessor_;
+  successor_optional successor_;
+  neighbor_sequence neighbor_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class type2: public ::xml_schema::type
+{
+  public:
+  // speed
+  //
+  typedef ::speed1 speed_type;
+  typedef ::xsd::cxx::tree::optional< speed_type > speed_optional;
+  typedef ::xsd::cxx::tree::traits< speed_type, char > speed_traits;
+
+  const speed_optional&
+  speed () const;
+
+  speed_optional&
+  speed ();
+
+  void
+  speed (const speed_type& x);
+
+  void
+  speed (const speed_optional& x);
+
+  void
+  speed (::std::unique_ptr< speed_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // type
+  //
+  typedef ::roadType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  type2 ();
+
+  type2 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  type2 (const type2& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual type2*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  type2&
+  operator= (const type2& x);
+
+  virtual 
+  ~type2 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  speed_optional speed_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  type_optional type_;
+};
+
+class planView: public ::xml_schema::type
+{
+  public:
+  // geometry
+  //
+  typedef ::geometry geometry_type;
+  typedef ::xsd::cxx::tree::sequence< geometry_type > geometry_sequence;
+  typedef geometry_sequence::iterator geometry_iterator;
+  typedef geometry_sequence::const_iterator geometry_const_iterator;
+  typedef ::xsd::cxx::tree::traits< geometry_type, char > geometry_traits;
+
+  const geometry_sequence&
+  geometry () const;
+
+  geometry_sequence&
+  geometry ();
+
+  void
+  geometry (const geometry_sequence& s);
+
+  // Constructors.
+  //
+  planView ();
+
+  planView (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  planView (const planView& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual planView*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  planView&
+  operator= (const planView& x);
+
+  virtual 
+  ~planView ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  geometry_sequence geometry_;
+};
+
+class elevationProfile: public ::xml_schema::type
+{
+  public:
+  // elevation
+  //
+  typedef ::elevation elevation_type;
+  typedef ::xsd::cxx::tree::sequence< elevation_type > elevation_sequence;
+  typedef elevation_sequence::iterator elevation_iterator;
+  typedef elevation_sequence::const_iterator elevation_const_iterator;
+  typedef ::xsd::cxx::tree::traits< elevation_type, char > elevation_traits;
+
+  const elevation_sequence&
+  elevation () const;
+
+  elevation_sequence&
+  elevation ();
+
+  void
+  elevation (const elevation_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  elevationProfile ();
+
+  elevationProfile (const ::xercesc::DOMElement& e,
+                    ::xml_schema::flags f = 0,
+                    ::xml_schema::container* c = 0);
+
+  elevationProfile (const elevationProfile& x,
+                    ::xml_schema::flags f = 0,
+                    ::xml_schema::container* c = 0);
+
+  virtual elevationProfile*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  elevationProfile&
+  operator= (const elevationProfile& x);
+
+  virtual 
+  ~elevationProfile ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  elevation_sequence elevation_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class lateralProfile: public ::xml_schema::type
+{
+  public:
+  // superelevation
+  //
+  typedef ::superelevation superelevation_type;
+  typedef ::xsd::cxx::tree::sequence< superelevation_type > superelevation_sequence;
+  typedef superelevation_sequence::iterator superelevation_iterator;
+  typedef superelevation_sequence::const_iterator superelevation_const_iterator;
+  typedef ::xsd::cxx::tree::traits< superelevation_type, char > superelevation_traits;
+
+  const superelevation_sequence&
+  superelevation () const;
+
+  superelevation_sequence&
+  superelevation ();
+
+  void
+  superelevation (const superelevation_sequence& s);
+
+  // crossfall
+  //
+  typedef ::crossfall crossfall_type;
+  typedef ::xsd::cxx::tree::sequence< crossfall_type > crossfall_sequence;
+  typedef crossfall_sequence::iterator crossfall_iterator;
+  typedef crossfall_sequence::const_iterator crossfall_const_iterator;
+  typedef ::xsd::cxx::tree::traits< crossfall_type, char > crossfall_traits;
+
+  const crossfall_sequence&
+  crossfall () const;
+
+  crossfall_sequence&
+  crossfall ();
+
+  void
+  crossfall (const crossfall_sequence& s);
+
+  // shape
+  //
+  typedef ::shape shape_type;
+  typedef ::xsd::cxx::tree::sequence< shape_type > shape_sequence;
+  typedef shape_sequence::iterator shape_iterator;
+  typedef shape_sequence::const_iterator shape_const_iterator;
+  typedef ::xsd::cxx::tree::traits< shape_type, char > shape_traits;
+
+  const shape_sequence&
+  shape () const;
+
+  shape_sequence&
+  shape ();
+
+  void
+  shape (const shape_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  lateralProfile ();
+
+  lateralProfile (const ::xercesc::DOMElement& e,
+                  ::xml_schema::flags f = 0,
+                  ::xml_schema::container* c = 0);
+
+  lateralProfile (const lateralProfile& x,
+                  ::xml_schema::flags f = 0,
+                  ::xml_schema::container* c = 0);
+
+  virtual lateralProfile*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  lateralProfile&
+  operator= (const lateralProfile& x);
+
+  virtual 
+  ~lateralProfile ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  superelevation_sequence superelevation_;
+  crossfall_sequence crossfall_;
+  shape_sequence shape_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class lanes: public ::xml_schema::type
+{
+  public:
+  // laneOffset
+  //
+  typedef ::laneOffset laneOffset_type;
+  typedef ::xsd::cxx::tree::sequence< laneOffset_type > laneOffset_sequence;
+  typedef laneOffset_sequence::iterator laneOffset_iterator;
+  typedef laneOffset_sequence::const_iterator laneOffset_const_iterator;
+  typedef ::xsd::cxx::tree::traits< laneOffset_type, char > laneOffset_traits;
+
+  const laneOffset_sequence&
+  laneOffset () const;
+
+  laneOffset_sequence&
+  laneOffset ();
+
+  void
+  laneOffset (const laneOffset_sequence& s);
+
+  // laneSection
+  //
+  typedef ::laneSection laneSection_type;
+  typedef ::xsd::cxx::tree::sequence< laneSection_type > laneSection_sequence;
+  typedef laneSection_sequence::iterator laneSection_iterator;
+  typedef laneSection_sequence::const_iterator laneSection_const_iterator;
+  typedef ::xsd::cxx::tree::traits< laneSection_type, char > laneSection_traits;
+
+  const laneSection_sequence&
+  laneSection () const;
+
+  laneSection_sequence&
+  laneSection ();
+
+  void
+  laneSection (const laneSection_sequence& s);
+
+  // Constructors.
+  //
+  lanes ();
+
+  lanes (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  lanes (const lanes& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual lanes*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  lanes&
+  operator= (const lanes& x);
+
+  virtual 
+  ~lanes ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  laneOffset_sequence laneOffset_;
+  laneSection_sequence laneSection_;
+};
+
+class objects: public ::xml_schema::type
+{
+  public:
+  // object
+  //
+  typedef ::object object_type;
+  typedef ::xsd::cxx::tree::sequence< object_type > object_sequence;
+  typedef object_sequence::iterator object_iterator;
+  typedef object_sequence::const_iterator object_const_iterator;
+  typedef ::xsd::cxx::tree::traits< object_type, char > object_traits;
+
+  const object_sequence&
+  object () const;
+
+  object_sequence&
+  object ();
+
+  void
+  object (const object_sequence& s);
+
+  // objectReference
+  //
+  typedef ::objectReference objectReference_type;
+  typedef ::xsd::cxx::tree::sequence< objectReference_type > objectReference_sequence;
+  typedef objectReference_sequence::iterator objectReference_iterator;
+  typedef objectReference_sequence::const_iterator objectReference_const_iterator;
+  typedef ::xsd::cxx::tree::traits< objectReference_type, char > objectReference_traits;
+
+  const objectReference_sequence&
+  objectReference () const;
+
+  objectReference_sequence&
+  objectReference ();
+
+  void
+  objectReference (const objectReference_sequence& s);
+
+  // tunnel
+  //
+  typedef ::tunnel tunnel_type;
+  typedef ::xsd::cxx::tree::sequence< tunnel_type > tunnel_sequence;
+  typedef tunnel_sequence::iterator tunnel_iterator;
+  typedef tunnel_sequence::const_iterator tunnel_const_iterator;
+  typedef ::xsd::cxx::tree::traits< tunnel_type, char > tunnel_traits;
+
+  const tunnel_sequence&
+  tunnel () const;
+
+  tunnel_sequence&
+  tunnel ();
+
+  void
+  tunnel (const tunnel_sequence& s);
+
+  // bridge
+  //
+  typedef ::bridge bridge_type;
+  typedef ::xsd::cxx::tree::sequence< bridge_type > bridge_sequence;
+  typedef bridge_sequence::iterator bridge_iterator;
+  typedef bridge_sequence::const_iterator bridge_const_iterator;
+  typedef ::xsd::cxx::tree::traits< bridge_type, char > bridge_traits;
+
+  const bridge_sequence&
+  bridge () const;
+
+  bridge_sequence&
+  bridge ();
+
+  void
+  bridge (const bridge_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  objects ();
+
+  objects (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  objects (const objects& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual objects*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  objects&
+  operator= (const objects& x);
+
+  virtual 
+  ~objects ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  object_sequence object_;
+  objectReference_sequence objectReference_;
+  tunnel_sequence tunnel_;
+  bridge_sequence bridge_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class signals: public ::xml_schema::type
+{
+  public:
+  // signal
+  //
+  typedef ::signal signal_type;
+  typedef ::xsd::cxx::tree::sequence< signal_type > signal_sequence;
+  typedef signal_sequence::iterator signal_iterator;
+  typedef signal_sequence::const_iterator signal_const_iterator;
+  typedef ::xsd::cxx::tree::traits< signal_type, char > signal_traits;
+
+  const signal_sequence&
+  signal () const;
+
+  signal_sequence&
+  signal ();
+
+  void
+  signal (const signal_sequence& s);
+
+  // signalReference
+  //
+  typedef ::signalReference signalReference_type;
+  typedef ::xsd::cxx::tree::sequence< signalReference_type > signalReference_sequence;
+  typedef signalReference_sequence::iterator signalReference_iterator;
+  typedef signalReference_sequence::const_iterator signalReference_const_iterator;
+  typedef ::xsd::cxx::tree::traits< signalReference_type, char > signalReference_traits;
+
+  const signalReference_sequence&
+  signalReference () const;
+
+  signalReference_sequence&
+  signalReference ();
+
+  void
+  signalReference (const signalReference_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  signals ();
+
+  signals (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  signals (const signals& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual signals*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  signals&
+  operator= (const signals& x);
+
+  virtual 
+  ~signals ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  signal_sequence signal_;
+  signalReference_sequence signalReference_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class surface: public ::xml_schema::type
+{
+  public:
+  // CRG
+  //
+  typedef ::CRG CRG_type;
+  typedef ::xsd::cxx::tree::sequence< CRG_type > CRG_sequence;
+  typedef CRG_sequence::iterator CRG_iterator;
+  typedef CRG_sequence::const_iterator CRG_const_iterator;
+  typedef ::xsd::cxx::tree::traits< CRG_type, char > CRG_traits;
+
+  const CRG_sequence&
+  CRG () const;
+
+  CRG_sequence&
+  CRG ();
+
+  void
+  CRG (const CRG_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  surface ();
+
+  surface (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  surface (const surface& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual surface*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  surface&
+  operator= (const surface& x);
+
+  virtual 
+  ~surface ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  CRG_sequence CRG_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class railroad: public ::xml_schema::type
+{
+  public:
+  // switch
+  //
+  typedef ::switch_ switch_type;
+  typedef ::xsd::cxx::tree::sequence< switch_type > switch_sequence;
+  typedef switch_sequence::iterator switch_iterator;
+  typedef switch_sequence::const_iterator switch_const_iterator;
+  typedef ::xsd::cxx::tree::traits< switch_type, char > switch_traits;
+
+  const switch_sequence&
+  switch_ () const;
+
+  switch_sequence&
+  switch_ ();
+
+  void
+  switch_ (const switch_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  railroad ();
+
+  railroad (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  railroad (const railroad& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual railroad*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  railroad&
+  operator= (const railroad& x);
+
+  virtual 
+  ~railroad ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  switch_sequence switch__;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class control: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // signalId
+  //
+  typedef ::xml_schema::string signalId_type;
+  typedef ::xsd::cxx::tree::optional< signalId_type > signalId_optional;
+  typedef ::xsd::cxx::tree::traits< signalId_type, char > signalId_traits;
+
+  const signalId_optional&
+  signalId () const;
+
+  signalId_optional&
+  signalId ();
+
+  void
+  signalId (const signalId_type& x);
+
+  void
+  signalId (const signalId_optional& x);
+
+  void
+  signalId (::std::unique_ptr< signalId_type > p);
+
+  // type
+  //
+  typedef ::xml_schema::string type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  control ();
+
+  control (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  control (const control& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual control*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  control&
+  operator= (const control& x);
+
+  virtual 
+  ~control ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  signalId_optional signalId_;
+  type_optional type_;
+};
+
+class connection: public ::xml_schema::type
+{
+  public:
+  // laneLink
+  //
+  typedef ::laneLink laneLink_type;
+  typedef ::xsd::cxx::tree::sequence< laneLink_type > laneLink_sequence;
+  typedef laneLink_sequence::iterator laneLink_iterator;
+  typedef laneLink_sequence::const_iterator laneLink_const_iterator;
+  typedef ::xsd::cxx::tree::traits< laneLink_type, char > laneLink_traits;
+
+  const laneLink_sequence&
+  laneLink () const;
+
+  laneLink_sequence&
+  laneLink ();
+
+  void
+  laneLink (const laneLink_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // incomingRoad
+  //
+  typedef ::xml_schema::string incomingRoad_type;
+  typedef ::xsd::cxx::tree::optional< incomingRoad_type > incomingRoad_optional;
+  typedef ::xsd::cxx::tree::traits< incomingRoad_type, char > incomingRoad_traits;
+
+  const incomingRoad_optional&
+  incomingRoad () const;
+
+  incomingRoad_optional&
+  incomingRoad ();
+
+  void
+  incomingRoad (const incomingRoad_type& x);
+
+  void
+  incomingRoad (const incomingRoad_optional& x);
+
+  void
+  incomingRoad (::std::unique_ptr< incomingRoad_type > p);
+
+  // connectingRoad
+  //
+  typedef ::xml_schema::string connectingRoad_type;
+  typedef ::xsd::cxx::tree::optional< connectingRoad_type > connectingRoad_optional;
+  typedef ::xsd::cxx::tree::traits< connectingRoad_type, char > connectingRoad_traits;
+
+  const connectingRoad_optional&
+  connectingRoad () const;
+
+  connectingRoad_optional&
+  connectingRoad ();
+
+  void
+  connectingRoad (const connectingRoad_type& x);
+
+  void
+  connectingRoad (const connectingRoad_optional& x);
+
+  void
+  connectingRoad (::std::unique_ptr< connectingRoad_type > p);
+
+  // contactPoint
+  //
+  typedef ::contactPoint contactPoint_type;
+  typedef ::xsd::cxx::tree::optional< contactPoint_type > contactPoint_optional;
+  typedef ::xsd::cxx::tree::traits< contactPoint_type, char > contactPoint_traits;
+
+  const contactPoint_optional&
+  contactPoint () const;
+
+  contactPoint_optional&
+  contactPoint ();
+
+  void
+  contactPoint (const contactPoint_type& x);
+
+  void
+  contactPoint (const contactPoint_optional& x);
+
+  void
+  contactPoint (::std::unique_ptr< contactPoint_type > p);
+
+  // Constructors.
+  //
+  connection ();
+
+  connection (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  connection (const connection& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual connection*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  connection&
+  operator= (const connection& x);
+
+  virtual 
+  ~connection ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  laneLink_sequence laneLink_;
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  incomingRoad_optional incomingRoad_;
+  connectingRoad_optional connectingRoad_;
+  contactPoint_optional contactPoint_;
+};
+
+class priority: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // high
+  //
+  typedef ::xml_schema::string high_type;
+  typedef ::xsd::cxx::tree::optional< high_type > high_optional;
+  typedef ::xsd::cxx::tree::traits< high_type, char > high_traits;
+
+  const high_optional&
+  high () const;
+
+  high_optional&
+  high ();
+
+  void
+  high (const high_type& x);
+
+  void
+  high (const high_optional& x);
+
+  void
+  high (::std::unique_ptr< high_type > p);
+
+  // low
+  //
+  typedef ::xml_schema::string low_type;
+  typedef ::xsd::cxx::tree::optional< low_type > low_optional;
+  typedef ::xsd::cxx::tree::traits< low_type, char > low_traits;
+
+  const low_optional&
+  low () const;
+
+  low_optional&
+  low ();
+
+  void
+  low (const low_type& x);
+
+  void
+  low (const low_optional& x);
+
+  void
+  low (::std::unique_ptr< low_type > p);
+
+  // Constructors.
+  //
+  priority ();
+
+  priority (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  priority (const priority& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual priority*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  priority&
+  operator= (const priority& x);
+
+  virtual 
+  ~priority ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  high_optional high_;
+  low_optional low_;
+};
+
+class controller1: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::xml_schema::string type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // sequence
+  //
+  typedef ::xml_schema::int_ sequence_type;
+  typedef ::xsd::cxx::tree::optional< sequence_type > sequence_optional;
+  typedef ::xsd::cxx::tree::traits< sequence_type, char > sequence_traits;
+
+  const sequence_optional&
+  sequence () const;
+
+  sequence_optional&
+  sequence ();
+
+  void
+  sequence (const sequence_type& x);
+
+  void
+  sequence (const sequence_optional& x);
+
+  // Constructors.
+  //
+  controller1 ();
+
+  controller1 (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  controller1 (const controller1& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual controller1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  controller1&
+  operator= (const controller1& x);
+
+  virtual 
+  ~controller1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  type_optional type_;
+  sequence_optional sequence_;
+};
+
+class junctionReference: public ::xml_schema::type
+{
+  public:
+  // junction
+  //
+  typedef ::xml_schema::string junction_type;
+  typedef ::xsd::cxx::tree::optional< junction_type > junction_optional;
+  typedef ::xsd::cxx::tree::traits< junction_type, char > junction_traits;
+
+  const junction_optional&
+  junction () const;
+
+  junction_optional&
+  junction ();
+
+  void
+  junction (const junction_type& x);
+
+  void
+  junction (const junction_optional& x);
+
+  void
+  junction (::std::unique_ptr< junction_type > p);
+
+  // Constructors.
+  //
+  junctionReference ();
+
+  junctionReference (const ::xercesc::DOMElement& e,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  junctionReference (const junctionReference& x,
+                     ::xml_schema::flags f = 0,
+                     ::xml_schema::container* c = 0);
+
+  virtual junctionReference*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  junctionReference&
+  operator= (const junctionReference& x);
+
+  virtual 
+  ~junctionReference ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  junction_optional junction_;
+};
+
+class platform: public ::xml_schema::type
+{
+  public:
+  // segment
+  //
+  typedef ::segment segment_type;
+  typedef ::xsd::cxx::tree::sequence< segment_type > segment_sequence;
+  typedef segment_sequence::iterator segment_iterator;
+  typedef segment_sequence::const_iterator segment_const_iterator;
+  typedef ::xsd::cxx::tree::traits< segment_type, char > segment_traits;
+
+  const segment_sequence&
+  segment () const;
+
+  segment_sequence&
+  segment ();
+
+  void
+  segment (const segment_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // Constructors.
+  //
+  platform ();
+
+  platform (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  platform (const platform& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual platform*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  platform&
+  operator= (const platform& x);
+
+  virtual 
+  ~platform ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  segment_sequence segment_;
+  name_optional name_;
+  id_optional id_;
+};
+
+class line: public ::xml_schema::type
+{
+  public:
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // space
+  //
+  typedef ::xml_schema::double_ space_type;
+  typedef ::xsd::cxx::tree::optional< space_type > space_optional;
+  typedef ::xsd::cxx::tree::traits< space_type, char, ::xsd::cxx::tree::schema_type::double_ > space_traits;
+
+  const space_optional&
+  space () const;
+
+  space_optional&
+  space ();
+
+  void
+  space (const space_type& x);
+
+  void
+  space (const space_optional& x);
+
+  // tOffset
+  //
+  typedef ::xml_schema::double_ tOffset_type;
+  typedef ::xsd::cxx::tree::optional< tOffset_type > tOffset_optional;
+  typedef ::xsd::cxx::tree::traits< tOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > tOffset_traits;
+
+  const tOffset_optional&
+  tOffset () const;
+
+  tOffset_optional&
+  tOffset ();
+
+  void
+  tOffset (const tOffset_type& x);
+
+  void
+  tOffset (const tOffset_optional& x);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // rule
+  //
+  typedef ::rule rule_type;
+  typedef ::xsd::cxx::tree::optional< rule_type > rule_optional;
+  typedef ::xsd::cxx::tree::traits< rule_type, char > rule_traits;
+
+  const rule_optional&
+  rule () const;
+
+  rule_optional&
+  rule ();
+
+  void
+  rule (const rule_type& x);
+
+  void
+  rule (const rule_optional& x);
+
+  void
+  rule (::std::unique_ptr< rule_type > p);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // Constructors.
+  //
+  line ();
+
+  line (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  line (const line& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual line*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  line&
+  operator= (const line& x);
+
+  virtual 
+  ~line ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  length_optional length_;
+  space_optional space_;
+  tOffset_optional tOffset_;
+  sOffset_optional sOffset_;
+  rule_optional rule_;
+  width_optional width_;
+};
+
+class predecessor1: public ::xml_schema::type
+{
+  public:
+  // elementType
+  //
+  typedef ::elementType elementType_type;
+  typedef ::xsd::cxx::tree::optional< elementType_type > elementType_optional;
+  typedef ::xsd::cxx::tree::traits< elementType_type, char > elementType_traits;
+
+  const elementType_optional&
+  elementType () const;
+
+  elementType_optional&
+  elementType ();
+
+  void
+  elementType (const elementType_type& x);
+
+  void
+  elementType (const elementType_optional& x);
+
+  void
+  elementType (::std::unique_ptr< elementType_type > p);
+
+  // elementId
+  //
+  typedef ::xml_schema::string elementId_type;
+  typedef ::xsd::cxx::tree::optional< elementId_type > elementId_optional;
+  typedef ::xsd::cxx::tree::traits< elementId_type, char > elementId_traits;
+
+  const elementId_optional&
+  elementId () const;
+
+  elementId_optional&
+  elementId ();
+
+  void
+  elementId (const elementId_type& x);
+
+  void
+  elementId (const elementId_optional& x);
+
+  void
+  elementId (::std::unique_ptr< elementId_type > p);
+
+  // contactPoint
+  //
+  typedef ::contactPoint contactPoint_type;
+  typedef ::xsd::cxx::tree::optional< contactPoint_type > contactPoint_optional;
+  typedef ::xsd::cxx::tree::traits< contactPoint_type, char > contactPoint_traits;
+
+  const contactPoint_optional&
+  contactPoint () const;
+
+  contactPoint_optional&
+  contactPoint ();
+
+  void
+  contactPoint (const contactPoint_type& x);
+
+  void
+  contactPoint (const contactPoint_optional& x);
+
+  void
+  contactPoint (::std::unique_ptr< contactPoint_type > p);
+
+  // Constructors.
+  //
+  predecessor1 ();
+
+  predecessor1 (const ::xercesc::DOMElement& e,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  predecessor1 (const predecessor1& x,
+                ::xml_schema::flags f = 0,
+                ::xml_schema::container* c = 0);
+
+  virtual predecessor1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  predecessor1&
+  operator= (const predecessor1& x);
+
+  virtual 
+  ~predecessor1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  elementType_optional elementType_;
+  elementId_optional elementId_;
+  contactPoint_optional contactPoint_;
+};
+
+class successor1: public ::xml_schema::type
+{
+  public:
+  // elementType
+  //
+  typedef ::elementType elementType_type;
+  typedef ::xsd::cxx::tree::optional< elementType_type > elementType_optional;
+  typedef ::xsd::cxx::tree::traits< elementType_type, char > elementType_traits;
+
+  const elementType_optional&
+  elementType () const;
+
+  elementType_optional&
+  elementType ();
+
+  void
+  elementType (const elementType_type& x);
+
+  void
+  elementType (const elementType_optional& x);
+
+  void
+  elementType (::std::unique_ptr< elementType_type > p);
+
+  // elementId
+  //
+  typedef ::xml_schema::string elementId_type;
+  typedef ::xsd::cxx::tree::optional< elementId_type > elementId_optional;
+  typedef ::xsd::cxx::tree::traits< elementId_type, char > elementId_traits;
+
+  const elementId_optional&
+  elementId () const;
+
+  elementId_optional&
+  elementId ();
+
+  void
+  elementId (const elementId_type& x);
+
+  void
+  elementId (const elementId_optional& x);
+
+  void
+  elementId (::std::unique_ptr< elementId_type > p);
+
+  // contactPoint
+  //
+  typedef ::contactPoint contactPoint_type;
+  typedef ::xsd::cxx::tree::optional< contactPoint_type > contactPoint_optional;
+  typedef ::xsd::cxx::tree::traits< contactPoint_type, char > contactPoint_traits;
+
+  const contactPoint_optional&
+  contactPoint () const;
+
+  contactPoint_optional&
+  contactPoint ();
+
+  void
+  contactPoint (const contactPoint_type& x);
+
+  void
+  contactPoint (const contactPoint_optional& x);
+
+  void
+  contactPoint (::std::unique_ptr< contactPoint_type > p);
+
+  // Constructors.
+  //
+  successor1 ();
+
+  successor1 (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  successor1 (const successor1& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual successor1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  successor1&
+  operator= (const successor1& x);
+
+  virtual 
+  ~successor1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  elementType_optional elementType_;
+  elementId_optional elementId_;
+  contactPoint_optional contactPoint_;
+};
+
+class neighbor: public ::xml_schema::type
+{
+  public:
+  // side
+  //
+  typedef ::side side_type;
+  typedef ::xsd::cxx::tree::optional< side_type > side_optional;
+  typedef ::xsd::cxx::tree::traits< side_type, char > side_traits;
+
+  const side_optional&
+  side () const;
+
+  side_optional&
+  side ();
+
+  void
+  side (const side_type& x);
+
+  void
+  side (const side_optional& x);
+
+  void
+  side (::std::unique_ptr< side_type > p);
+
+  // elementId
+  //
+  typedef ::xml_schema::string elementId_type;
+  typedef ::xsd::cxx::tree::optional< elementId_type > elementId_optional;
+  typedef ::xsd::cxx::tree::traits< elementId_type, char > elementId_traits;
+
+  const elementId_optional&
+  elementId () const;
+
+  elementId_optional&
+  elementId ();
+
+  void
+  elementId (const elementId_type& x);
+
+  void
+  elementId (const elementId_optional& x);
+
+  void
+  elementId (::std::unique_ptr< elementId_type > p);
+
+  // direction
+  //
+  typedef ::direction direction_type;
+  typedef ::xsd::cxx::tree::optional< direction_type > direction_optional;
+  typedef ::xsd::cxx::tree::traits< direction_type, char > direction_traits;
+
+  const direction_optional&
+  direction () const;
+
+  direction_optional&
+  direction ();
+
+  void
+  direction (const direction_type& x);
+
+  void
+  direction (const direction_optional& x);
+
+  void
+  direction (::std::unique_ptr< direction_type > p);
+
+  // Constructors.
+  //
+  neighbor ();
+
+  neighbor (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  neighbor (const neighbor& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual neighbor*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  neighbor&
+  operator= (const neighbor& x);
+
+  virtual 
+  ~neighbor ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  side_optional side_;
+  elementId_optional elementId_;
+  direction_optional direction_;
+};
+
+class speed1: public ::xml_schema::type
+{
+  public:
+  // max
+  //
+  typedef ::max max_type;
+  typedef ::xsd::cxx::tree::optional< max_type > max_optional;
+  typedef ::xsd::cxx::tree::traits< max_type, char > max_traits;
+
+  const max_optional&
+  max () const;
+
+  max_optional&
+  max ();
+
+  void
+  max (const max_type& x);
+
+  void
+  max (const max_optional& x);
+
+  void
+  max (::std::unique_ptr< max_type > p);
+
+  // unit
+  //
+  typedef ::unit unit_type;
+  typedef ::xsd::cxx::tree::optional< unit_type > unit_optional;
+  typedef ::xsd::cxx::tree::traits< unit_type, char > unit_traits;
+
+  const unit_optional&
+  unit () const;
+
+  unit_optional&
+  unit ();
+
+  void
+  unit (const unit_type& x);
+
+  void
+  unit (const unit_optional& x);
+
+  void
+  unit (::std::unique_ptr< unit_type > p);
+
+  // Constructors.
+  //
+  speed1 ();
+
+  speed1 (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  speed1 (const speed1& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual speed1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  speed1&
+  operator= (const speed1& x);
+
+  virtual 
+  ~speed1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  max_optional max_;
+  unit_optional unit_;
+};
+
+class geometry: public ::xml_schema::type
+{
+  public:
+  // line
+  //
+  typedef ::line1 line_type;
+  typedef ::xsd::cxx::tree::optional< line_type > line_optional;
+  typedef ::xsd::cxx::tree::traits< line_type, char > line_traits;
+
+  const line_optional&
+  line () const;
+
+  line_optional&
+  line ();
+
+  void
+  line (const line_type& x);
+
+  void
+  line (const line_optional& x);
+
+  void
+  line (::std::unique_ptr< line_type > p);
+
+  // spiral
+  //
+  typedef ::spiral spiral_type;
+  typedef ::xsd::cxx::tree::optional< spiral_type > spiral_optional;
+  typedef ::xsd::cxx::tree::traits< spiral_type, char > spiral_traits;
+
+  const spiral_optional&
+  spiral () const;
+
+  spiral_optional&
+  spiral ();
+
+  void
+  spiral (const spiral_type& x);
+
+  void
+  spiral (const spiral_optional& x);
+
+  void
+  spiral (::std::unique_ptr< spiral_type > p);
+
+  // arc
+  //
+  typedef ::arc arc_type;
+  typedef ::xsd::cxx::tree::optional< arc_type > arc_optional;
+  typedef ::xsd::cxx::tree::traits< arc_type, char > arc_traits;
+
+  const arc_optional&
+  arc () const;
+
+  arc_optional&
+  arc ();
+
+  void
+  arc (const arc_type& x);
+
+  void
+  arc (const arc_optional& x);
+
+  void
+  arc (::std::unique_ptr< arc_type > p);
+
+  // poly3
+  //
+  typedef ::poly3 poly3_type;
+  typedef ::xsd::cxx::tree::optional< poly3_type > poly3_optional;
+  typedef ::xsd::cxx::tree::traits< poly3_type, char > poly3_traits;
+
+  const poly3_optional&
+  poly3 () const;
+
+  poly3_optional&
+  poly3 ();
+
+  void
+  poly3 (const poly3_type& x);
+
+  void
+  poly3 (const poly3_optional& x);
+
+  void
+  poly3 (::std::unique_ptr< poly3_type > p);
+
+  // paramPoly3
+  //
+  typedef ::paramPoly3 paramPoly3_type;
+  typedef ::xsd::cxx::tree::optional< paramPoly3_type > paramPoly3_optional;
+  typedef ::xsd::cxx::tree::traits< paramPoly3_type, char > paramPoly3_traits;
+
+  const paramPoly3_optional&
+  paramPoly3 () const;
+
+  paramPoly3_optional&
+  paramPoly3 ();
+
+  void
+  paramPoly3 (const paramPoly3_type& x);
+
+  void
+  paramPoly3 (const paramPoly3_optional& x);
+
+  void
+  paramPoly3 (::std::unique_ptr< paramPoly3_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // x
+  //
+  typedef ::xml_schema::double_ x_type;
+  typedef ::xsd::cxx::tree::optional< x_type > x_optional;
+  typedef ::xsd::cxx::tree::traits< x_type, char, ::xsd::cxx::tree::schema_type::double_ > x_traits;
+
+  const x_optional&
+  x () const;
+
+  x_optional&
+  x ();
+
+  void
+  x (const x_type& x);
+
+  void
+  x (const x_optional& x);
+
+  // y
+  //
+  typedef ::xml_schema::double_ y_type;
+  typedef ::xsd::cxx::tree::optional< y_type > y_optional;
+  typedef ::xsd::cxx::tree::traits< y_type, char, ::xsd::cxx::tree::schema_type::double_ > y_traits;
+
+  const y_optional&
+  y () const;
+
+  y_optional&
+  y ();
+
+  void
+  y (const y_type& x);
+
+  void
+  y (const y_optional& x);
+
+  // hdg
+  //
+  typedef ::xml_schema::double_ hdg_type;
+  typedef ::xsd::cxx::tree::optional< hdg_type > hdg_optional;
+  typedef ::xsd::cxx::tree::traits< hdg_type, char, ::xsd::cxx::tree::schema_type::double_ > hdg_traits;
+
+  const hdg_optional&
+  hdg () const;
+
+  hdg_optional&
+  hdg ();
+
+  void
+  hdg (const hdg_type& x);
+
+  void
+  hdg (const hdg_optional& x);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // Constructors.
+  //
+  geometry ();
+
+  geometry (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  geometry (const geometry& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual geometry*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  geometry&
+  operator= (const geometry& x);
+
+  virtual 
+  ~geometry ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  line_optional line_;
+  spiral_optional spiral_;
+  arc_optional arc_;
+  poly3_optional poly3_;
+  paramPoly3_optional paramPoly3_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  x_optional x_;
+  y_optional y_;
+  hdg_optional hdg_;
+  length_optional length_;
+};
+
+class elevation: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  elevation ();
+
+  elevation (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  elevation (const elevation& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual elevation*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  elevation&
+  operator= (const elevation& x);
+
+  virtual 
+  ~elevation ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class superelevation: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  superelevation ();
+
+  superelevation (const ::xercesc::DOMElement& e,
+                  ::xml_schema::flags f = 0,
+                  ::xml_schema::container* c = 0);
+
+  superelevation (const superelevation& x,
+                  ::xml_schema::flags f = 0,
+                  ::xml_schema::container* c = 0);
+
+  virtual superelevation*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  superelevation&
+  operator= (const superelevation& x);
+
+  virtual 
+  ~superelevation ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class crossfall: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // side
+  //
+  typedef ::crossfallSide side_type;
+  typedef ::xsd::cxx::tree::optional< side_type > side_optional;
+  typedef ::xsd::cxx::tree::traits< side_type, char > side_traits;
+
+  const side_optional&
+  side () const;
+
+  side_optional&
+  side ();
+
+  void
+  side (const side_type& x);
+
+  void
+  side (const side_optional& x);
+
+  void
+  side (::std::unique_ptr< side_type > p);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  crossfall ();
+
+  crossfall (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  crossfall (const crossfall& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual crossfall*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  crossfall&
+  operator= (const crossfall& x);
+
+  virtual 
+  ~crossfall ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  side_optional side_;
+  s_optional s_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class shape: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  shape ();
+
+  shape (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  shape (const shape& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual shape*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  shape&
+  operator= (const shape& x);
+
+  virtual 
+  ~shape ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  t_optional t_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class laneOffset: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  laneOffset ();
+
+  laneOffset (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  laneOffset (const laneOffset& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual laneOffset*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneOffset&
+  operator= (const laneOffset& x);
+
+  virtual 
+  ~laneOffset ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class laneSection: public ::xml_schema::type
+{
+  public:
+  // left
+  //
+  typedef ::left left_type;
+  typedef ::xsd::cxx::tree::optional< left_type > left_optional;
+  typedef ::xsd::cxx::tree::traits< left_type, char > left_traits;
+
+  const left_optional&
+  left () const;
+
+  left_optional&
+  left ();
+
+  void
+  left (const left_type& x);
+
+  void
+  left (const left_optional& x);
+
+  void
+  left (::std::unique_ptr< left_type > p);
+
+  // center
+  //
+  typedef ::center center_type;
+  typedef ::xsd::cxx::tree::traits< center_type, char > center_traits;
+
+  const center_type&
+  center () const;
+
+  center_type&
+  center ();
+
+  void
+  center (const center_type& x);
+
+  void
+  center (::std::unique_ptr< center_type > p);
+
+  // right
+  //
+  typedef ::right right_type;
+  typedef ::xsd::cxx::tree::optional< right_type > right_optional;
+  typedef ::xsd::cxx::tree::traits< right_type, char > right_traits;
+
+  const right_optional&
+  right () const;
+
+  right_optional&
+  right ();
+
+  void
+  right (const right_type& x);
+
+  void
+  right (const right_optional& x);
+
+  void
+  right (::std::unique_ptr< right_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // singleSide
+  //
+  typedef ::singleSide singleSide_type;
+  typedef ::xsd::cxx::tree::optional< singleSide_type > singleSide_optional;
+  typedef ::xsd::cxx::tree::traits< singleSide_type, char > singleSide_traits;
+
+  const singleSide_optional&
+  singleSide () const;
+
+  singleSide_optional&
+  singleSide ();
+
+  void
+  singleSide (const singleSide_type& x);
+
+  void
+  singleSide (const singleSide_optional& x);
+
+  void
+  singleSide (::std::unique_ptr< singleSide_type > p);
+
+  // Constructors.
+  //
+  laneSection (const center_type&);
+
+  laneSection (::std::unique_ptr< center_type >);
+
+  laneSection (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  laneSection (const laneSection& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual laneSection*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneSection&
+  operator= (const laneSection& x);
+
+  virtual 
+  ~laneSection ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  left_optional left_;
+  ::xsd::cxx::tree::one< center_type > center_;
+  right_optional right_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  singleSide_optional singleSide_;
+};
+
+class object: public ::xml_schema::type
+{
+  public:
+  // repeat
+  //
+  typedef ::repeat repeat_type;
+  typedef ::xsd::cxx::tree::sequence< repeat_type > repeat_sequence;
+  typedef repeat_sequence::iterator repeat_iterator;
+  typedef repeat_sequence::const_iterator repeat_const_iterator;
+  typedef ::xsd::cxx::tree::traits< repeat_type, char > repeat_traits;
+
+  const repeat_sequence&
+  repeat () const;
+
+  repeat_sequence&
+  repeat ();
+
+  void
+  repeat (const repeat_sequence& s);
+
+  // outline
+  //
+  typedef ::outline outline_type;
+  typedef ::xsd::cxx::tree::optional< outline_type > outline_optional;
+  typedef ::xsd::cxx::tree::traits< outline_type, char > outline_traits;
+
+  const outline_optional&
+  outline () const;
+
+  outline_optional&
+  outline ();
+
+  void
+  outline (const outline_type& x);
+
+  void
+  outline (const outline_optional& x);
+
+  void
+  outline (::std::unique_ptr< outline_type > p);
+
+  // material
+  //
+  typedef ::material1 material_type;
+  typedef ::xsd::cxx::tree::optional< material_type > material_optional;
+  typedef ::xsd::cxx::tree::traits< material_type, char > material_traits;
+
+  const material_optional&
+  material () const;
+
+  material_optional&
+  material ();
+
+  void
+  material (const material_type& x);
+
+  void
+  material (const material_optional& x);
+
+  void
+  material (::std::unique_ptr< material_type > p);
+
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // parkingSpace
+  //
+  typedef ::parkingSpace parkingSpace_type;
+  typedef ::xsd::cxx::tree::optional< parkingSpace_type > parkingSpace_optional;
+  typedef ::xsd::cxx::tree::traits< parkingSpace_type, char > parkingSpace_traits;
+
+  const parkingSpace_optional&
+  parkingSpace () const;
+
+  parkingSpace_optional&
+  parkingSpace ();
+
+  void
+  parkingSpace (const parkingSpace_type& x);
+
+  void
+  parkingSpace (const parkingSpace_optional& x);
+
+  void
+  parkingSpace (::std::unique_ptr< parkingSpace_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // type
+  //
+  typedef ::xml_schema::string type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // zOffset
+  //
+  typedef ::xml_schema::double_ zOffset_type;
+  typedef ::xsd::cxx::tree::optional< zOffset_type > zOffset_optional;
+  typedef ::xsd::cxx::tree::traits< zOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffset_traits;
+
+  const zOffset_optional&
+  zOffset () const;
+
+  zOffset_optional&
+  zOffset ();
+
+  void
+  zOffset (const zOffset_type& x);
+
+  void
+  zOffset (const zOffset_optional& x);
+
+  // validLength
+  //
+  typedef ::xml_schema::double_ validLength_type;
+  typedef ::xsd::cxx::tree::optional< validLength_type > validLength_optional;
+  typedef ::xsd::cxx::tree::traits< validLength_type, char, ::xsd::cxx::tree::schema_type::double_ > validLength_traits;
+
+  const validLength_optional&
+  validLength () const;
+
+  validLength_optional&
+  validLength ();
+
+  void
+  validLength (const validLength_type& x);
+
+  void
+  validLength (const validLength_optional& x);
+
+  // orientation
+  //
+  typedef ::orientation orientation_type;
+  typedef ::xsd::cxx::tree::optional< orientation_type > orientation_optional;
+  typedef ::xsd::cxx::tree::traits< orientation_type, char > orientation_traits;
+
+  const orientation_optional&
+  orientation () const;
+
+  orientation_optional&
+  orientation ();
+
+  void
+  orientation (const orientation_type& x);
+
+  void
+  orientation (const orientation_optional& x);
+
+  void
+  orientation (::std::unique_ptr< orientation_type > p);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // radius
+  //
+  typedef ::xml_schema::double_ radius_type;
+  typedef ::xsd::cxx::tree::optional< radius_type > radius_optional;
+  typedef ::xsd::cxx::tree::traits< radius_type, char, ::xsd::cxx::tree::schema_type::double_ > radius_traits;
+
+  const radius_optional&
+  radius () const;
+
+  radius_optional&
+  radius ();
+
+  void
+  radius (const radius_type& x);
+
+  void
+  radius (const radius_optional& x);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // hdg
+  //
+  typedef ::xml_schema::double_ hdg_type;
+  typedef ::xsd::cxx::tree::optional< hdg_type > hdg_optional;
+  typedef ::xsd::cxx::tree::traits< hdg_type, char, ::xsd::cxx::tree::schema_type::double_ > hdg_traits;
+
+  const hdg_optional&
+  hdg () const;
+
+  hdg_optional&
+  hdg ();
+
+  void
+  hdg (const hdg_type& x);
+
+  void
+  hdg (const hdg_optional& x);
+
+  // pitch
+  //
+  typedef ::xml_schema::double_ pitch_type;
+  typedef ::xsd::cxx::tree::optional< pitch_type > pitch_optional;
+  typedef ::xsd::cxx::tree::traits< pitch_type, char, ::xsd::cxx::tree::schema_type::double_ > pitch_traits;
+
+  const pitch_optional&
+  pitch () const;
+
+  pitch_optional&
+  pitch ();
+
+  void
+  pitch (const pitch_type& x);
+
+  void
+  pitch (const pitch_optional& x);
+
+  // roll
+  //
+  typedef ::xml_schema::double_ roll_type;
+  typedef ::xsd::cxx::tree::optional< roll_type > roll_optional;
+  typedef ::xsd::cxx::tree::traits< roll_type, char, ::xsd::cxx::tree::schema_type::double_ > roll_traits;
+
+  const roll_optional&
+  roll () const;
+
+  roll_optional&
+  roll ();
+
+  void
+  roll (const roll_type& x);
+
+  void
+  roll (const roll_optional& x);
+
+  // Constructors.
+  //
+  object ();
+
+  object (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  object (const object& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual object*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  object&
+  operator= (const object& x);
+
+  virtual 
+  ~object ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  repeat_sequence repeat_;
+  outline_optional outline_;
+  material_optional material_;
+  validity_sequence validity_;
+  parkingSpace_optional parkingSpace_;
+  userData_sequence userData_;
+  include_sequence include_;
+  type_optional type_;
+  name_optional name_;
+  id_optional id_;
+  s_optional s_;
+  t_optional t_;
+  zOffset_optional zOffset_;
+  validLength_optional validLength_;
+  orientation_optional orientation_;
+  length_optional length_;
+  width_optional width_;
+  radius_optional radius_;
+  height_optional height_;
+  hdg_optional hdg_;
+  pitch_optional pitch_;
+  roll_optional roll_;
+};
+
+class objectReference: public ::xml_schema::type
+{
+  public:
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // zOffset
+  //
+  typedef ::xml_schema::double_ zOffset_type;
+  typedef ::xsd::cxx::tree::optional< zOffset_type > zOffset_optional;
+  typedef ::xsd::cxx::tree::traits< zOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffset_traits;
+
+  const zOffset_optional&
+  zOffset () const;
+
+  zOffset_optional&
+  zOffset ();
+
+  void
+  zOffset (const zOffset_type& x);
+
+  void
+  zOffset (const zOffset_optional& x);
+
+  // validLength
+  //
+  typedef ::xml_schema::double_ validLength_type;
+  typedef ::xsd::cxx::tree::optional< validLength_type > validLength_optional;
+  typedef ::xsd::cxx::tree::traits< validLength_type, char, ::xsd::cxx::tree::schema_type::double_ > validLength_traits;
+
+  const validLength_optional&
+  validLength () const;
+
+  validLength_optional&
+  validLength ();
+
+  void
+  validLength (const validLength_type& x);
+
+  void
+  validLength (const validLength_optional& x);
+
+  // orientation
+  //
+  typedef ::orientation orientation_type;
+  typedef ::xsd::cxx::tree::optional< orientation_type > orientation_optional;
+  typedef ::xsd::cxx::tree::traits< orientation_type, char > orientation_traits;
+
+  const orientation_optional&
+  orientation () const;
+
+  orientation_optional&
+  orientation ();
+
+  void
+  orientation (const orientation_type& x);
+
+  void
+  orientation (const orientation_optional& x);
+
+  void
+  orientation (::std::unique_ptr< orientation_type > p);
+
+  // Constructors.
+  //
+  objectReference ();
+
+  objectReference (const ::xercesc::DOMElement& e,
+                   ::xml_schema::flags f = 0,
+                   ::xml_schema::container* c = 0);
+
+  objectReference (const objectReference& x,
+                   ::xml_schema::flags f = 0,
+                   ::xml_schema::container* c = 0);
+
+  virtual objectReference*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  objectReference&
+  operator= (const objectReference& x);
+
+  virtual 
+  ~objectReference ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  validity_sequence validity_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  t_optional t_;
+  id_optional id_;
+  zOffset_optional zOffset_;
+  validLength_optional validLength_;
+  orientation_optional orientation_;
+};
+
+class tunnel: public ::xml_schema::type
+{
+  public:
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::tunnelType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // lighting
+  //
+  typedef ::xml_schema::double_ lighting_type;
+  typedef ::xsd::cxx::tree::optional< lighting_type > lighting_optional;
+  typedef ::xsd::cxx::tree::traits< lighting_type, char, ::xsd::cxx::tree::schema_type::double_ > lighting_traits;
+
+  const lighting_optional&
+  lighting () const;
+
+  lighting_optional&
+  lighting ();
+
+  void
+  lighting (const lighting_type& x);
+
+  void
+  lighting (const lighting_optional& x);
+
+  // daylight
+  //
+  typedef ::xml_schema::double_ daylight_type;
+  typedef ::xsd::cxx::tree::optional< daylight_type > daylight_optional;
+  typedef ::xsd::cxx::tree::traits< daylight_type, char, ::xsd::cxx::tree::schema_type::double_ > daylight_traits;
+
+  const daylight_optional&
+  daylight () const;
+
+  daylight_optional&
+  daylight ();
+
+  void
+  daylight (const daylight_type& x);
+
+  void
+  daylight (const daylight_optional& x);
+
+  // Constructors.
+  //
+  tunnel ();
+
+  tunnel (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  tunnel (const tunnel& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual tunnel*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  tunnel&
+  operator= (const tunnel& x);
+
+  virtual 
+  ~tunnel ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  validity_sequence validity_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  length_optional length_;
+  name_optional name_;
+  id_optional id_;
+  type_optional type_;
+  lighting_optional lighting_;
+  daylight_optional daylight_;
+};
+
+class bridge: public ::xml_schema::type
+{
+  public:
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::bridgeType type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  bridge ();
+
+  bridge (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  bridge (const bridge& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual bridge*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  bridge&
+  operator= (const bridge& x);
+
+  virtual 
+  ~bridge ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  validity_sequence validity_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  length_optional length_;
+  name_optional name_;
+  id_optional id_;
+  type_optional type_;
+};
+
+class signal: public ::xml_schema::type
+{
+  public:
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // dependency
+  //
+  typedef ::dependency dependency_type;
+  typedef ::xsd::cxx::tree::sequence< dependency_type > dependency_sequence;
+  typedef dependency_sequence::iterator dependency_iterator;
+  typedef dependency_sequence::const_iterator dependency_const_iterator;
+  typedef ::xsd::cxx::tree::traits< dependency_type, char > dependency_traits;
+
+  const dependency_sequence&
+  dependency () const;
+
+  dependency_sequence&
+  dependency ();
+
+  void
+  dependency (const dependency_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // dynamic
+  //
+  typedef ::dynamic dynamic_type;
+  typedef ::xsd::cxx::tree::optional< dynamic_type > dynamic_optional;
+  typedef ::xsd::cxx::tree::traits< dynamic_type, char > dynamic_traits;
+
+  const dynamic_optional&
+  dynamic () const;
+
+  dynamic_optional&
+  dynamic ();
+
+  void
+  dynamic (const dynamic_type& x);
+
+  void
+  dynamic (const dynamic_optional& x);
+
+  void
+  dynamic (::std::unique_ptr< dynamic_type > p);
+
+  // orientation
+  //
+  typedef ::orientation orientation_type;
+  typedef ::xsd::cxx::tree::optional< orientation_type > orientation_optional;
+  typedef ::xsd::cxx::tree::traits< orientation_type, char > orientation_traits;
+
+  const orientation_optional&
+  orientation () const;
+
+  orientation_optional&
+  orientation ();
+
+  void
+  orientation (const orientation_type& x);
+
+  void
+  orientation (const orientation_optional& x);
+
+  void
+  orientation (::std::unique_ptr< orientation_type > p);
+
+  // zOffset
+  //
+  typedef ::xml_schema::double_ zOffset_type;
+  typedef ::xsd::cxx::tree::optional< zOffset_type > zOffset_optional;
+  typedef ::xsd::cxx::tree::traits< zOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffset_traits;
+
+  const zOffset_optional&
+  zOffset () const;
+
+  zOffset_optional&
+  zOffset ();
+
+  void
+  zOffset (const zOffset_type& x);
+
+  void
+  zOffset (const zOffset_optional& x);
+
+  // country
+  //
+  typedef ::xml_schema::string country_type;
+  typedef ::xsd::cxx::tree::optional< country_type > country_optional;
+  typedef ::xsd::cxx::tree::traits< country_type, char > country_traits;
+
+  const country_optional&
+  country () const;
+
+  country_optional&
+  country ();
+
+  void
+  country (const country_type& x);
+
+  void
+  country (const country_optional& x);
+
+  void
+  country (::std::unique_ptr< country_type > p);
+
+  // type
+  //
+  typedef ::xml_schema::string type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // subtype
+  //
+  typedef ::xml_schema::string subtype_type;
+  typedef ::xsd::cxx::tree::optional< subtype_type > subtype_optional;
+  typedef ::xsd::cxx::tree::traits< subtype_type, char > subtype_traits;
+
+  const subtype_optional&
+  subtype () const;
+
+  subtype_optional&
+  subtype ();
+
+  void
+  subtype (const subtype_type& x);
+
+  void
+  subtype (const subtype_optional& x);
+
+  void
+  subtype (::std::unique_ptr< subtype_type > p);
+
+  // value
+  //
+  typedef ::xml_schema::double_ value_type;
+  typedef ::xsd::cxx::tree::optional< value_type > value_optional;
+  typedef ::xsd::cxx::tree::traits< value_type, char, ::xsd::cxx::tree::schema_type::double_ > value_traits;
+
+  const value_optional&
+  value () const;
+
+  value_optional&
+  value ();
+
+  void
+  value (const value_type& x);
+
+  void
+  value (const value_optional& x);
+
+  // unit
+  //
+  typedef ::unit unit_type;
+  typedef ::xsd::cxx::tree::optional< unit_type > unit_optional;
+  typedef ::xsd::cxx::tree::traits< unit_type, char > unit_traits;
+
+  const unit_optional&
+  unit () const;
+
+  unit_optional&
+  unit ();
+
+  void
+  unit (const unit_type& x);
+
+  void
+  unit (const unit_optional& x);
+
+  void
+  unit (::std::unique_ptr< unit_type > p);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // width
+  //
+  typedef ::xml_schema::double_ width_type;
+  typedef ::xsd::cxx::tree::optional< width_type > width_optional;
+  typedef ::xsd::cxx::tree::traits< width_type, char, ::xsd::cxx::tree::schema_type::double_ > width_traits;
+
+  const width_optional&
+  width () const;
+
+  width_optional&
+  width ();
+
+  void
+  width (const width_type& x);
+
+  void
+  width (const width_optional& x);
+
+  // text
+  //
+  typedef ::xml_schema::string text_type;
+  typedef ::xsd::cxx::tree::optional< text_type > text_optional;
+  typedef ::xsd::cxx::tree::traits< text_type, char > text_traits;
+
+  const text_optional&
+  text () const;
+
+  text_optional&
+  text ();
+
+  void
+  text (const text_type& x);
+
+  void
+  text (const text_optional& x);
+
+  void
+  text (::std::unique_ptr< text_type > p);
+
+  // hOffset
+  //
+  typedef ::xml_schema::double_ hOffset_type;
+  typedef ::xsd::cxx::tree::optional< hOffset_type > hOffset_optional;
+  typedef ::xsd::cxx::tree::traits< hOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > hOffset_traits;
+
+  const hOffset_optional&
+  hOffset () const;
+
+  hOffset_optional&
+  hOffset ();
+
+  void
+  hOffset (const hOffset_type& x);
+
+  void
+  hOffset (const hOffset_optional& x);
+
+  // pitch
+  //
+  typedef ::xml_schema::double_ pitch_type;
+  typedef ::xsd::cxx::tree::optional< pitch_type > pitch_optional;
+  typedef ::xsd::cxx::tree::traits< pitch_type, char, ::xsd::cxx::tree::schema_type::double_ > pitch_traits;
+
+  const pitch_optional&
+  pitch () const;
+
+  pitch_optional&
+  pitch ();
+
+  void
+  pitch (const pitch_type& x);
+
+  void
+  pitch (const pitch_optional& x);
+
+  // roll
+  //
+  typedef ::xml_schema::double_ roll_type;
+  typedef ::xsd::cxx::tree::optional< roll_type > roll_optional;
+  typedef ::xsd::cxx::tree::traits< roll_type, char, ::xsd::cxx::tree::schema_type::double_ > roll_traits;
+
+  const roll_optional&
+  roll () const;
+
+  roll_optional&
+  roll ();
+
+  void
+  roll (const roll_type& x);
+
+  void
+  roll (const roll_optional& x);
+
+  // Constructors.
+  //
+  signal ();
+
+  signal (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  signal (const signal& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual signal*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  signal&
+  operator= (const signal& x);
+
+  virtual 
+  ~signal ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  validity_sequence validity_;
+  dependency_sequence dependency_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  t_optional t_;
+  id_optional id_;
+  name_optional name_;
+  dynamic_optional dynamic_;
+  orientation_optional orientation_;
+  zOffset_optional zOffset_;
+  country_optional country_;
+  type_optional type_;
+  subtype_optional subtype_;
+  value_optional value_;
+  unit_optional unit_;
+  height_optional height_;
+  width_optional width_;
+  text_optional text_;
+  hOffset_optional hOffset_;
+  pitch_optional pitch_;
+  roll_optional roll_;
+};
+
+class signalReference: public ::xml_schema::type
+{
+  public:
+  // validity
+  //
+  typedef ::laneValidity validity_type;
+  typedef ::xsd::cxx::tree::sequence< validity_type > validity_sequence;
+  typedef validity_sequence::iterator validity_iterator;
+  typedef validity_sequence::const_iterator validity_const_iterator;
+  typedef ::xsd::cxx::tree::traits< validity_type, char > validity_traits;
+
+  const validity_sequence&
+  validity () const;
+
+  validity_sequence&
+  validity ();
+
+  void
+  validity (const validity_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // orientation
+  //
+  typedef ::orientation orientation_type;
+  typedef ::xsd::cxx::tree::optional< orientation_type > orientation_optional;
+  typedef ::xsd::cxx::tree::traits< orientation_type, char > orientation_traits;
+
+  const orientation_optional&
+  orientation () const;
+
+  orientation_optional&
+  orientation ();
+
+  void
+  orientation (const orientation_type& x);
+
+  void
+  orientation (const orientation_optional& x);
+
+  void
+  orientation (::std::unique_ptr< orientation_type > p);
+
+  // Constructors.
+  //
+  signalReference ();
+
+  signalReference (const ::xercesc::DOMElement& e,
+                   ::xml_schema::flags f = 0,
+                   ::xml_schema::container* c = 0);
+
+  signalReference (const signalReference& x,
+                   ::xml_schema::flags f = 0,
+                   ::xml_schema::container* c = 0);
+
+  virtual signalReference*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  signalReference&
+  operator= (const signalReference& x);
+
+  virtual 
+  ~signalReference ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  validity_sequence validity_;
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  t_optional t_;
+  id_optional id_;
+  orientation_optional orientation_;
+};
+
+class CRG: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // file
+  //
+  typedef ::xml_schema::string file_type;
+  typedef ::xsd::cxx::tree::optional< file_type > file_optional;
+  typedef ::xsd::cxx::tree::traits< file_type, char > file_traits;
+
+  const file_optional&
+  file () const;
+
+  file_optional&
+  file ();
+
+  void
+  file (const file_type& x);
+
+  void
+  file (const file_optional& x);
+
+  void
+  file (::std::unique_ptr< file_type > p);
+
+  // sStart
+  //
+  typedef ::xml_schema::double_ sStart_type;
+  typedef ::xsd::cxx::tree::optional< sStart_type > sStart_optional;
+  typedef ::xsd::cxx::tree::traits< sStart_type, char, ::xsd::cxx::tree::schema_type::double_ > sStart_traits;
+
+  const sStart_optional&
+  sStart () const;
+
+  sStart_optional&
+  sStart ();
+
+  void
+  sStart (const sStart_type& x);
+
+  void
+  sStart (const sStart_optional& x);
+
+  // sEnd
+  //
+  typedef ::xml_schema::double_ sEnd_type;
+  typedef ::xsd::cxx::tree::optional< sEnd_type > sEnd_optional;
+  typedef ::xsd::cxx::tree::traits< sEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > sEnd_traits;
+
+  const sEnd_optional&
+  sEnd () const;
+
+  sEnd_optional&
+  sEnd ();
+
+  void
+  sEnd (const sEnd_type& x);
+
+  void
+  sEnd (const sEnd_optional& x);
+
+  // orientation
+  //
+  typedef ::surfaceOrientation orientation_type;
+  typedef ::xsd::cxx::tree::optional< orientation_type > orientation_optional;
+  typedef ::xsd::cxx::tree::traits< orientation_type, char > orientation_traits;
+
+  const orientation_optional&
+  orientation () const;
+
+  orientation_optional&
+  orientation ();
+
+  void
+  orientation (const orientation_type& x);
+
+  void
+  orientation (const orientation_optional& x);
+
+  void
+  orientation (::std::unique_ptr< orientation_type > p);
+
+  // mode
+  //
+  typedef ::mode mode_type;
+  typedef ::xsd::cxx::tree::optional< mode_type > mode_optional;
+  typedef ::xsd::cxx::tree::traits< mode_type, char > mode_traits;
+
+  const mode_optional&
+  mode () const;
+
+  mode_optional&
+  mode ();
+
+  void
+  mode (const mode_type& x);
+
+  void
+  mode (const mode_optional& x);
+
+  void
+  mode (::std::unique_ptr< mode_type > p);
+
+  // purpose
+  //
+  typedef ::purpose purpose_type;
+  typedef ::xsd::cxx::tree::optional< purpose_type > purpose_optional;
+  typedef ::xsd::cxx::tree::traits< purpose_type, char > purpose_traits;
+
+  const purpose_optional&
+  purpose () const;
+
+  purpose_optional&
+  purpose ();
+
+  void
+  purpose (const purpose_type& x);
+
+  void
+  purpose (const purpose_optional& x);
+
+  void
+  purpose (::std::unique_ptr< purpose_type > p);
+
+  // sOffset
+  //
+  typedef ::xml_schema::double_ sOffset_type;
+  typedef ::xsd::cxx::tree::optional< sOffset_type > sOffset_optional;
+  typedef ::xsd::cxx::tree::traits< sOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > sOffset_traits;
+
+  const sOffset_optional&
+  sOffset () const;
+
+  sOffset_optional&
+  sOffset ();
+
+  void
+  sOffset (const sOffset_type& x);
+
+  void
+  sOffset (const sOffset_optional& x);
+
+  // tOffset
+  //
+  typedef ::xml_schema::double_ tOffset_type;
+  typedef ::xsd::cxx::tree::optional< tOffset_type > tOffset_optional;
+  typedef ::xsd::cxx::tree::traits< tOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > tOffset_traits;
+
+  const tOffset_optional&
+  tOffset () const;
+
+  tOffset_optional&
+  tOffset ();
+
+  void
+  tOffset (const tOffset_type& x);
+
+  void
+  tOffset (const tOffset_optional& x);
+
+  // zOffset
+  //
+  typedef ::xml_schema::double_ zOffset_type;
+  typedef ::xsd::cxx::tree::optional< zOffset_type > zOffset_optional;
+  typedef ::xsd::cxx::tree::traits< zOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffset_traits;
+
+  const zOffset_optional&
+  zOffset () const;
+
+  zOffset_optional&
+  zOffset ();
+
+  void
+  zOffset (const zOffset_type& x);
+
+  void
+  zOffset (const zOffset_optional& x);
+
+  // zScale
+  //
+  typedef ::xml_schema::double_ zScale_type;
+  typedef ::xsd::cxx::tree::optional< zScale_type > zScale_optional;
+  typedef ::xsd::cxx::tree::traits< zScale_type, char, ::xsd::cxx::tree::schema_type::double_ > zScale_traits;
+
+  const zScale_optional&
+  zScale () const;
+
+  zScale_optional&
+  zScale ();
+
+  void
+  zScale (const zScale_type& x);
+
+  void
+  zScale (const zScale_optional& x);
+
+  // hOffset
+  //
+  typedef ::xml_schema::double_ hOffset_type;
+  typedef ::xsd::cxx::tree::optional< hOffset_type > hOffset_optional;
+  typedef ::xsd::cxx::tree::traits< hOffset_type, char, ::xsd::cxx::tree::schema_type::double_ > hOffset_traits;
+
+  const hOffset_optional&
+  hOffset () const;
+
+  hOffset_optional&
+  hOffset ();
+
+  void
+  hOffset (const hOffset_type& x);
+
+  void
+  hOffset (const hOffset_optional& x);
+
+  // Constructors.
+  //
+  CRG ();
+
+  CRG (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  CRG (const CRG& x,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  virtual CRG*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  CRG&
+  operator= (const CRG& x);
+
+  virtual 
+  ~CRG ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  file_optional file_;
+  sStart_optional sStart_;
+  sEnd_optional sEnd_;
+  orientation_optional orientation_;
+  mode_optional mode_;
+  purpose_optional purpose_;
+  sOffset_optional sOffset_;
+  tOffset_optional tOffset_;
+  zOffset_optional zOffset_;
+  zScale_optional zScale_;
+  hOffset_optional hOffset_;
+};
+
+class switch_: public ::xml_schema::type
+{
+  public:
+  // mainTrack
+  //
+  typedef ::mainTrack mainTrack_type;
+  typedef ::xsd::cxx::tree::traits< mainTrack_type, char > mainTrack_traits;
+
+  const mainTrack_type&
+  mainTrack () const;
+
+  mainTrack_type&
+  mainTrack ();
+
+  void
+  mainTrack (const mainTrack_type& x);
+
+  void
+  mainTrack (::std::unique_ptr< mainTrack_type > p);
+
+  // sideTrack
+  //
+  typedef ::sideTrack sideTrack_type;
+  typedef ::xsd::cxx::tree::traits< sideTrack_type, char > sideTrack_traits;
+
+  const sideTrack_type&
+  sideTrack () const;
+
+  sideTrack_type&
+  sideTrack ();
+
+  void
+  sideTrack (const sideTrack_type& x);
+
+  void
+  sideTrack (::std::unique_ptr< sideTrack_type > p);
+
+  // partner
+  //
+  typedef ::partner partner_type;
+  typedef ::xsd::cxx::tree::optional< partner_type > partner_optional;
+  typedef ::xsd::cxx::tree::traits< partner_type, char > partner_traits;
+
+  const partner_optional&
+  partner () const;
+
+  partner_optional&
+  partner ();
+
+  void
+  partner (const partner_type& x);
+
+  void
+  partner (const partner_optional& x);
+
+  void
+  partner (::std::unique_ptr< partner_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // position
+  //
+  typedef ::position position_type;
+  typedef ::xsd::cxx::tree::optional< position_type > position_optional;
+  typedef ::xsd::cxx::tree::traits< position_type, char > position_traits;
+
+  const position_optional&
+  position () const;
+
+  position_optional&
+  position ();
+
+  void
+  position (const position_type& x);
+
+  void
+  position (const position_optional& x);
+
+  void
+  position (::std::unique_ptr< position_type > p);
+
+  // Constructors.
+  //
+  switch_ (const mainTrack_type&,
+           const sideTrack_type&);
+
+  switch_ (::std::unique_ptr< mainTrack_type >,
+           ::std::unique_ptr< sideTrack_type >);
+
+  switch_ (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  switch_ (const switch_& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual switch_*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  switch_&
+  operator= (const switch_& x);
+
+  virtual 
+  ~switch_ ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  ::xsd::cxx::tree::one< mainTrack_type > mainTrack_;
+  ::xsd::cxx::tree::one< sideTrack_type > sideTrack_;
+  partner_optional partner_;
+  userData_sequence userData_;
+  include_sequence include_;
+  name_optional name_;
+  id_optional id_;
+  position_optional position_;
+};
+
+class laneLink: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // from
+  //
+  typedef ::xml_schema::int_ from_type;
+  typedef ::xsd::cxx::tree::optional< from_type > from_optional;
+  typedef ::xsd::cxx::tree::traits< from_type, char > from_traits;
+
+  const from_optional&
+  from () const;
+
+  from_optional&
+  from ();
+
+  void
+  from (const from_type& x);
+
+  void
+  from (const from_optional& x);
+
+  // to
+  //
+  typedef ::xml_schema::int_ to_type;
+  typedef ::xsd::cxx::tree::optional< to_type > to_optional;
+  typedef ::xsd::cxx::tree::traits< to_type, char > to_traits;
+
+  const to_optional&
+  to () const;
+
+  to_optional&
+  to ();
+
+  void
+  to (const to_type& x);
+
+  void
+  to (const to_optional& x);
+
+  // Constructors.
+  //
+  laneLink ();
+
+  laneLink (const ::xercesc::DOMElement& e,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  laneLink (const laneLink& x,
+            ::xml_schema::flags f = 0,
+            ::xml_schema::container* c = 0);
+
+  virtual laneLink*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  laneLink&
+  operator= (const laneLink& x);
+
+  virtual 
+  ~laneLink ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  from_optional from_;
+  to_optional to_;
+};
+
+class segment: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // roadId
+  //
+  typedef ::xml_schema::string roadId_type;
+  typedef ::xsd::cxx::tree::optional< roadId_type > roadId_optional;
+  typedef ::xsd::cxx::tree::traits< roadId_type, char > roadId_traits;
+
+  const roadId_optional&
+  roadId () const;
+
+  roadId_optional&
+  roadId ();
+
+  void
+  roadId (const roadId_type& x);
+
+  void
+  roadId (const roadId_optional& x);
+
+  void
+  roadId (::std::unique_ptr< roadId_type > p);
+
+  // sStart
+  //
+  typedef ::xml_schema::double_ sStart_type;
+  typedef ::xsd::cxx::tree::optional< sStart_type > sStart_optional;
+  typedef ::xsd::cxx::tree::traits< sStart_type, char, ::xsd::cxx::tree::schema_type::double_ > sStart_traits;
+
+  const sStart_optional&
+  sStart () const;
+
+  sStart_optional&
+  sStart ();
+
+  void
+  sStart (const sStart_type& x);
+
+  void
+  sStart (const sStart_optional& x);
+
+  // sEnd
+  //
+  typedef ::xml_schema::double_ sEnd_type;
+  typedef ::xsd::cxx::tree::optional< sEnd_type > sEnd_optional;
+  typedef ::xsd::cxx::tree::traits< sEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > sEnd_traits;
+
+  const sEnd_optional&
+  sEnd () const;
+
+  sEnd_optional&
+  sEnd ();
+
+  void
+  sEnd (const sEnd_type& x);
+
+  void
+  sEnd (const sEnd_optional& x);
+
+  // side
+  //
+  typedef ::side side_type;
+  typedef ::xsd::cxx::tree::optional< side_type > side_optional;
+  typedef ::xsd::cxx::tree::traits< side_type, char > side_traits;
+
+  const side_optional&
+  side () const;
+
+  side_optional&
+  side ();
+
+  void
+  side (const side_type& x);
+
+  void
+  side (const side_optional& x);
+
+  void
+  side (::std::unique_ptr< side_type > p);
+
+  // Constructors.
+  //
+  segment ();
+
+  segment (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  segment (const segment& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual segment*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  segment&
+  operator= (const segment& x);
+
+  virtual 
+  ~segment ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  roadId_optional roadId_;
+  sStart_optional sStart_;
+  sEnd_optional sEnd_;
+  side_optional side_;
+};
+
+class line1: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  line1 ();
+
+  line1 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  line1 (const line1& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual line1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  line1&
+  operator= (const line1& x);
+
+  virtual 
+  ~line1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class spiral: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // curvStart
+  //
+  typedef ::xml_schema::double_ curvStart_type;
+  typedef ::xsd::cxx::tree::optional< curvStart_type > curvStart_optional;
+  typedef ::xsd::cxx::tree::traits< curvStart_type, char, ::xsd::cxx::tree::schema_type::double_ > curvStart_traits;
+
+  const curvStart_optional&
+  curvStart () const;
+
+  curvStart_optional&
+  curvStart ();
+
+  void
+  curvStart (const curvStart_type& x);
+
+  void
+  curvStart (const curvStart_optional& x);
+
+  // curvEnd
+  //
+  typedef ::xml_schema::double_ curvEnd_type;
+  typedef ::xsd::cxx::tree::optional< curvEnd_type > curvEnd_optional;
+  typedef ::xsd::cxx::tree::traits< curvEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > curvEnd_traits;
+
+  const curvEnd_optional&
+  curvEnd () const;
+
+  curvEnd_optional&
+  curvEnd ();
+
+  void
+  curvEnd (const curvEnd_type& x);
+
+  void
+  curvEnd (const curvEnd_optional& x);
+
+  // Constructors.
+  //
+  spiral ();
+
+  spiral (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  spiral (const spiral& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual spiral*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  spiral&
+  operator= (const spiral& x);
+
+  virtual 
+  ~spiral ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  curvStart_optional curvStart_;
+  curvEnd_optional curvEnd_;
+};
+
+class arc: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // curvature
+  //
+  typedef ::xml_schema::double_ curvature_type;
+  typedef ::xsd::cxx::tree::optional< curvature_type > curvature_optional;
+  typedef ::xsd::cxx::tree::traits< curvature_type, char, ::xsd::cxx::tree::schema_type::double_ > curvature_traits;
+
+  const curvature_optional&
+  curvature () const;
+
+  curvature_optional&
+  curvature ();
+
+  void
+  curvature (const curvature_type& x);
+
+  void
+  curvature (const curvature_optional& x);
+
+  // Constructors.
+  //
+  arc ();
+
+  arc (const ::xercesc::DOMElement& e,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  arc (const arc& x,
+       ::xml_schema::flags f = 0,
+       ::xml_schema::container* c = 0);
+
+  virtual arc*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  arc&
+  operator= (const arc& x);
+
+  virtual 
+  ~arc ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  curvature_optional curvature_;
+};
+
+class poly3: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // a
+  //
+  typedef ::xml_schema::double_ a_type;
+  typedef ::xsd::cxx::tree::optional< a_type > a_optional;
+  typedef ::xsd::cxx::tree::traits< a_type, char, ::xsd::cxx::tree::schema_type::double_ > a_traits;
+
+  const a_optional&
+  a () const;
+
+  a_optional&
+  a ();
+
+  void
+  a (const a_type& x);
+
+  void
+  a (const a_optional& x);
+
+  // b
+  //
+  typedef ::xml_schema::double_ b_type;
+  typedef ::xsd::cxx::tree::optional< b_type > b_optional;
+  typedef ::xsd::cxx::tree::traits< b_type, char, ::xsd::cxx::tree::schema_type::double_ > b_traits;
+
+  const b_optional&
+  b () const;
+
+  b_optional&
+  b ();
+
+  void
+  b (const b_type& x);
+
+  void
+  b (const b_optional& x);
+
+  // c
+  //
+  typedef ::xml_schema::double_ c_type;
+  typedef ::xsd::cxx::tree::optional< c_type > c_optional;
+  typedef ::xsd::cxx::tree::traits< c_type, char, ::xsd::cxx::tree::schema_type::double_ > c_traits;
+
+  const c_optional&
+  c () const;
+
+  c_optional&
+  c ();
+
+  void
+  c (const c_type& x);
+
+  void
+  c (const c_optional& x);
+
+  // d
+  //
+  typedef ::xml_schema::double_ d_type;
+  typedef ::xsd::cxx::tree::optional< d_type > d_optional;
+  typedef ::xsd::cxx::tree::traits< d_type, char, ::xsd::cxx::tree::schema_type::double_ > d_traits;
+
+  const d_optional&
+  d () const;
+
+  d_optional&
+  d ();
+
+  void
+  d (const d_type& x);
+
+  void
+  d (const d_optional& x);
+
+  // Constructors.
+  //
+  poly3 ();
+
+  poly3 (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  poly3 (const poly3& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual poly3*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  poly3&
+  operator= (const poly3& x);
+
+  virtual 
+  ~poly3 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  a_optional a_;
+  b_optional b_;
+  c_optional c_;
+  d_optional d_;
+};
+
+class paramPoly3: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // aU
+  //
+  typedef ::xml_schema::double_ aU_type;
+  typedef ::xsd::cxx::tree::optional< aU_type > aU_optional;
+  typedef ::xsd::cxx::tree::traits< aU_type, char, ::xsd::cxx::tree::schema_type::double_ > aU_traits;
+
+  const aU_optional&
+  aU () const;
+
+  aU_optional&
+  aU ();
+
+  void
+  aU (const aU_type& x);
+
+  void
+  aU (const aU_optional& x);
+
+  // bU
+  //
+  typedef ::xml_schema::double_ bU_type;
+  typedef ::xsd::cxx::tree::optional< bU_type > bU_optional;
+  typedef ::xsd::cxx::tree::traits< bU_type, char, ::xsd::cxx::tree::schema_type::double_ > bU_traits;
+
+  const bU_optional&
+  bU () const;
+
+  bU_optional&
+  bU ();
+
+  void
+  bU (const bU_type& x);
+
+  void
+  bU (const bU_optional& x);
+
+  // cU
+  //
+  typedef ::xml_schema::double_ cU_type;
+  typedef ::xsd::cxx::tree::optional< cU_type > cU_optional;
+  typedef ::xsd::cxx::tree::traits< cU_type, char, ::xsd::cxx::tree::schema_type::double_ > cU_traits;
+
+  const cU_optional&
+  cU () const;
+
+  cU_optional&
+  cU ();
+
+  void
+  cU (const cU_type& x);
+
+  void
+  cU (const cU_optional& x);
+
+  // dU
+  //
+  typedef ::xml_schema::double_ dU_type;
+  typedef ::xsd::cxx::tree::optional< dU_type > dU_optional;
+  typedef ::xsd::cxx::tree::traits< dU_type, char, ::xsd::cxx::tree::schema_type::double_ > dU_traits;
+
+  const dU_optional&
+  dU () const;
+
+  dU_optional&
+  dU ();
+
+  void
+  dU (const dU_type& x);
+
+  void
+  dU (const dU_optional& x);
+
+  // aV
+  //
+  typedef ::xml_schema::double_ aV_type;
+  typedef ::xsd::cxx::tree::optional< aV_type > aV_optional;
+  typedef ::xsd::cxx::tree::traits< aV_type, char, ::xsd::cxx::tree::schema_type::double_ > aV_traits;
+
+  const aV_optional&
+  aV () const;
+
+  aV_optional&
+  aV ();
+
+  void
+  aV (const aV_type& x);
+
+  void
+  aV (const aV_optional& x);
+
+  // bV
+  //
+  typedef ::xml_schema::double_ bV_type;
+  typedef ::xsd::cxx::tree::optional< bV_type > bV_optional;
+  typedef ::xsd::cxx::tree::traits< bV_type, char, ::xsd::cxx::tree::schema_type::double_ > bV_traits;
+
+  const bV_optional&
+  bV () const;
+
+  bV_optional&
+  bV ();
+
+  void
+  bV (const bV_type& x);
+
+  void
+  bV (const bV_optional& x);
+
+  // cV
+  //
+  typedef ::xml_schema::double_ cV_type;
+  typedef ::xsd::cxx::tree::optional< cV_type > cV_optional;
+  typedef ::xsd::cxx::tree::traits< cV_type, char, ::xsd::cxx::tree::schema_type::double_ > cV_traits;
+
+  const cV_optional&
+  cV () const;
+
+  cV_optional&
+  cV ();
+
+  void
+  cV (const cV_type& x);
+
+  void
+  cV (const cV_optional& x);
+
+  // dV
+  //
+  typedef ::xml_schema::double_ dV_type;
+  typedef ::xsd::cxx::tree::optional< dV_type > dV_optional;
+  typedef ::xsd::cxx::tree::traits< dV_type, char, ::xsd::cxx::tree::schema_type::double_ > dV_traits;
+
+  const dV_optional&
+  dV () const;
+
+  dV_optional&
+  dV ();
+
+  void
+  dV (const dV_type& x);
+
+  void
+  dV (const dV_optional& x);
+
+  // pRange
+  //
+  typedef ::pRange pRange_type;
+  typedef ::xsd::cxx::tree::optional< pRange_type > pRange_optional;
+  typedef ::xsd::cxx::tree::traits< pRange_type, char > pRange_traits;
+
+  const pRange_optional&
+  pRange () const;
+
+  pRange_optional&
+  pRange ();
+
+  void
+  pRange (const pRange_type& x);
+
+  void
+  pRange (const pRange_optional& x);
+
+  void
+  pRange (::std::unique_ptr< pRange_type > p);
+
+  // Constructors.
+  //
+  paramPoly3 ();
+
+  paramPoly3 (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  paramPoly3 (const paramPoly3& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual paramPoly3*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  paramPoly3&
+  operator= (const paramPoly3& x);
+
+  virtual 
+  ~paramPoly3 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  aU_optional aU_;
+  bU_optional bU_;
+  cU_optional cU_;
+  dU_optional dU_;
+  aV_optional aV_;
+  bV_optional bV_;
+  cV_optional cV_;
+  dV_optional dV_;
+  pRange_optional pRange_;
+};
+
+class left: public ::xml_schema::type
+{
+  public:
+  // lane
+  //
+  typedef ::lane lane_type;
+  typedef ::xsd::cxx::tree::sequence< lane_type > lane_sequence;
+  typedef lane_sequence::iterator lane_iterator;
+  typedef lane_sequence::const_iterator lane_const_iterator;
+  typedef ::xsd::cxx::tree::traits< lane_type, char > lane_traits;
+
+  const lane_sequence&
+  lane () const;
+
+  lane_sequence&
+  lane ();
+
+  void
+  lane (const lane_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  left ();
+
+  left (const ::xercesc::DOMElement& e,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  left (const left& x,
+        ::xml_schema::flags f = 0,
+        ::xml_schema::container* c = 0);
+
+  virtual left*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  left&
+  operator= (const left& x);
+
+  virtual 
+  ~left ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  lane_sequence lane_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class center: public ::xml_schema::type
+{
+  public:
+  // lane
+  //
+  typedef ::centerLane lane_type;
+  typedef ::xsd::cxx::tree::optional< lane_type > lane_optional;
+  typedef ::xsd::cxx::tree::traits< lane_type, char > lane_traits;
+
+  const lane_optional&
+  lane () const;
+
+  lane_optional&
+  lane ();
+
+  void
+  lane (const lane_type& x);
+
+  void
+  lane (const lane_optional& x);
+
+  void
+  lane (::std::unique_ptr< lane_type > p);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  center ();
+
+  center (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  center (const center& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual center*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  center&
+  operator= (const center& x);
+
+  virtual 
+  ~center ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  lane_optional lane_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class right: public ::xml_schema::type
+{
+  public:
+  // lane
+  //
+  typedef ::lane lane_type;
+  typedef ::xsd::cxx::tree::sequence< lane_type > lane_sequence;
+  typedef lane_sequence::iterator lane_iterator;
+  typedef lane_sequence::const_iterator lane_const_iterator;
+  typedef ::xsd::cxx::tree::traits< lane_type, char > lane_traits;
+
+  const lane_sequence&
+  lane () const;
+
+  lane_sequence&
+  lane ();
+
+  void
+  lane (const lane_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  right ();
+
+  right (const ::xercesc::DOMElement& e,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  right (const right& x,
+         ::xml_schema::flags f = 0,
+         ::xml_schema::container* c = 0);
+
+  virtual right*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  right&
+  operator= (const right& x);
+
+  virtual 
+  ~right ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  lane_sequence lane_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class repeat: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // length
+  //
+  typedef ::xml_schema::double_ length_type;
+  typedef ::xsd::cxx::tree::optional< length_type > length_optional;
+  typedef ::xsd::cxx::tree::traits< length_type, char, ::xsd::cxx::tree::schema_type::double_ > length_traits;
+
+  const length_optional&
+  length () const;
+
+  length_optional&
+  length ();
+
+  void
+  length (const length_type& x);
+
+  void
+  length (const length_optional& x);
+
+  // distance
+  //
+  typedef ::xml_schema::double_ distance_type;
+  typedef ::xsd::cxx::tree::optional< distance_type > distance_optional;
+  typedef ::xsd::cxx::tree::traits< distance_type, char, ::xsd::cxx::tree::schema_type::double_ > distance_traits;
+
+  const distance_optional&
+  distance () const;
+
+  distance_optional&
+  distance ();
+
+  void
+  distance (const distance_type& x);
+
+  void
+  distance (const distance_optional& x);
+
+  // tStart
+  //
+  typedef ::xml_schema::double_ tStart_type;
+  typedef ::xsd::cxx::tree::optional< tStart_type > tStart_optional;
+  typedef ::xsd::cxx::tree::traits< tStart_type, char, ::xsd::cxx::tree::schema_type::double_ > tStart_traits;
+
+  const tStart_optional&
+  tStart () const;
+
+  tStart_optional&
+  tStart ();
+
+  void
+  tStart (const tStart_type& x);
+
+  void
+  tStart (const tStart_optional& x);
+
+  // tEnd
+  //
+  typedef ::xml_schema::double_ tEnd_type;
+  typedef ::xsd::cxx::tree::optional< tEnd_type > tEnd_optional;
+  typedef ::xsd::cxx::tree::traits< tEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > tEnd_traits;
+
+  const tEnd_optional&
+  tEnd () const;
+
+  tEnd_optional&
+  tEnd ();
+
+  void
+  tEnd (const tEnd_type& x);
+
+  void
+  tEnd (const tEnd_optional& x);
+
+  // widthStart
+  //
+  typedef ::xml_schema::double_ widthStart_type;
+  typedef ::xsd::cxx::tree::optional< widthStart_type > widthStart_optional;
+  typedef ::xsd::cxx::tree::traits< widthStart_type, char, ::xsd::cxx::tree::schema_type::double_ > widthStart_traits;
+
+  const widthStart_optional&
+  widthStart () const;
+
+  widthStart_optional&
+  widthStart ();
+
+  void
+  widthStart (const widthStart_type& x);
+
+  void
+  widthStart (const widthStart_optional& x);
+
+  // widthEnd
+  //
+  typedef ::xml_schema::double_ widthEnd_type;
+  typedef ::xsd::cxx::tree::optional< widthEnd_type > widthEnd_optional;
+  typedef ::xsd::cxx::tree::traits< widthEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > widthEnd_traits;
+
+  const widthEnd_optional&
+  widthEnd () const;
+
+  widthEnd_optional&
+  widthEnd ();
+
+  void
+  widthEnd (const widthEnd_type& x);
+
+  void
+  widthEnd (const widthEnd_optional& x);
+
+  // heightStart
+  //
+  typedef ::xml_schema::double_ heightStart_type;
+  typedef ::xsd::cxx::tree::optional< heightStart_type > heightStart_optional;
+  typedef ::xsd::cxx::tree::traits< heightStart_type, char, ::xsd::cxx::tree::schema_type::double_ > heightStart_traits;
+
+  const heightStart_optional&
+  heightStart () const;
+
+  heightStart_optional&
+  heightStart ();
+
+  void
+  heightStart (const heightStart_type& x);
+
+  void
+  heightStart (const heightStart_optional& x);
+
+  // heightEnd
+  //
+  typedef ::xml_schema::double_ heightEnd_type;
+  typedef ::xsd::cxx::tree::optional< heightEnd_type > heightEnd_optional;
+  typedef ::xsd::cxx::tree::traits< heightEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > heightEnd_traits;
+
+  const heightEnd_optional&
+  heightEnd () const;
+
+  heightEnd_optional&
+  heightEnd ();
+
+  void
+  heightEnd (const heightEnd_type& x);
+
+  void
+  heightEnd (const heightEnd_optional& x);
+
+  // zOffsetStart
+  //
+  typedef ::xml_schema::double_ zOffsetStart_type;
+  typedef ::xsd::cxx::tree::optional< zOffsetStart_type > zOffsetStart_optional;
+  typedef ::xsd::cxx::tree::traits< zOffsetStart_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffsetStart_traits;
+
+  const zOffsetStart_optional&
+  zOffsetStart () const;
+
+  zOffsetStart_optional&
+  zOffsetStart ();
+
+  void
+  zOffsetStart (const zOffsetStart_type& x);
+
+  void
+  zOffsetStart (const zOffsetStart_optional& x);
+
+  // zOffsetEnd
+  //
+  typedef ::xml_schema::double_ zOffsetEnd_type;
+  typedef ::xsd::cxx::tree::optional< zOffsetEnd_type > zOffsetEnd_optional;
+  typedef ::xsd::cxx::tree::traits< zOffsetEnd_type, char, ::xsd::cxx::tree::schema_type::double_ > zOffsetEnd_traits;
+
+  const zOffsetEnd_optional&
+  zOffsetEnd () const;
+
+  zOffsetEnd_optional&
+  zOffsetEnd ();
+
+  void
+  zOffsetEnd (const zOffsetEnd_type& x);
+
+  void
+  zOffsetEnd (const zOffsetEnd_optional& x);
+
+  // Constructors.
+  //
+  repeat ();
+
+  repeat (const ::xercesc::DOMElement& e,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  repeat (const repeat& x,
+          ::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0);
+
+  virtual repeat*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  repeat&
+  operator= (const repeat& x);
+
+  virtual 
+  ~repeat ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  length_optional length_;
+  distance_optional distance_;
+  tStart_optional tStart_;
+  tEnd_optional tEnd_;
+  widthStart_optional widthStart_;
+  widthEnd_optional widthEnd_;
+  heightStart_optional heightStart_;
+  heightEnd_optional heightEnd_;
+  zOffsetStart_optional zOffsetStart_;
+  zOffsetEnd_optional zOffsetEnd_;
+};
+
+class outline: public ::xml_schema::type
+{
+  public:
+  // cornerRoad
+  //
+  typedef ::cornerRoad cornerRoad_type;
+  typedef ::xsd::cxx::tree::sequence< cornerRoad_type > cornerRoad_sequence;
+  typedef cornerRoad_sequence::iterator cornerRoad_iterator;
+  typedef cornerRoad_sequence::const_iterator cornerRoad_const_iterator;
+  typedef ::xsd::cxx::tree::traits< cornerRoad_type, char > cornerRoad_traits;
+
+  const cornerRoad_sequence&
+  cornerRoad () const;
+
+  cornerRoad_sequence&
+  cornerRoad ();
+
+  void
+  cornerRoad (const cornerRoad_sequence& s);
+
+  // cornerLocal
+  //
+  typedef ::cornerLocal cornerLocal_type;
+  typedef ::xsd::cxx::tree::sequence< cornerLocal_type > cornerLocal_sequence;
+  typedef cornerLocal_sequence::iterator cornerLocal_iterator;
+  typedef cornerLocal_sequence::const_iterator cornerLocal_const_iterator;
+  typedef ::xsd::cxx::tree::traits< cornerLocal_type, char > cornerLocal_traits;
+
+  const cornerLocal_sequence&
+  cornerLocal () const;
+
+  cornerLocal_sequence&
+  cornerLocal ();
+
+  void
+  cornerLocal (const cornerLocal_sequence& s);
+
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // Constructors.
+  //
+  outline ();
+
+  outline (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  outline (const outline& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual outline*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  outline&
+  operator= (const outline& x);
+
+  virtual 
+  ~outline ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  cornerRoad_sequence cornerRoad_;
+  cornerLocal_sequence cornerLocal_;
+  userData_sequence userData_;
+  include_sequence include_;
+};
+
+class material1: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // surface
+  //
+  typedef ::xml_schema::string surface_type;
+  typedef ::xsd::cxx::tree::optional< surface_type > surface_optional;
+  typedef ::xsd::cxx::tree::traits< surface_type, char > surface_traits;
+
+  const surface_optional&
+  surface () const;
+
+  surface_optional&
+  surface ();
+
+  void
+  surface (const surface_type& x);
+
+  void
+  surface (const surface_optional& x);
+
+  void
+  surface (::std::unique_ptr< surface_type > p);
+
+  // friction
+  //
+  typedef ::xml_schema::double_ friction_type;
+  typedef ::xsd::cxx::tree::optional< friction_type > friction_optional;
+  typedef ::xsd::cxx::tree::traits< friction_type, char, ::xsd::cxx::tree::schema_type::double_ > friction_traits;
+
+  const friction_optional&
+  friction () const;
+
+  friction_optional&
+  friction ();
+
+  void
+  friction (const friction_type& x);
+
+  void
+  friction (const friction_optional& x);
+
+  // roughness
+  //
+  typedef ::xml_schema::double_ roughness_type;
+  typedef ::xsd::cxx::tree::optional< roughness_type > roughness_optional;
+  typedef ::xsd::cxx::tree::traits< roughness_type, char, ::xsd::cxx::tree::schema_type::double_ > roughness_traits;
+
+  const roughness_optional&
+  roughness () const;
+
+  roughness_optional&
+  roughness ();
+
+  void
+  roughness (const roughness_type& x);
+
+  void
+  roughness (const roughness_optional& x);
+
+  // Constructors.
+  //
+  material1 ();
+
+  material1 (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  material1 (const material1& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual material1*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  material1&
+  operator= (const material1& x);
+
+  virtual 
+  ~material1 ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  surface_optional surface_;
+  friction_optional friction_;
+  roughness_optional roughness_;
+};
+
+class dependency: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // type
+  //
+  typedef ::xml_schema::string type_type;
+  typedef ::xsd::cxx::tree::optional< type_type > type_optional;
+  typedef ::xsd::cxx::tree::traits< type_type, char > type_traits;
+
+  const type_optional&
+  type () const;
+
+  type_optional&
+  type ();
+
+  void
+  type (const type_type& x);
+
+  void
+  type (const type_optional& x);
+
+  void
+  type (::std::unique_ptr< type_type > p);
+
+  // Constructors.
+  //
+  dependency ();
+
+  dependency (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  dependency (const dependency& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual dependency*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  dependency&
+  operator= (const dependency& x);
+
+  virtual 
+  ~dependency ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  id_optional id_;
+  type_optional type_;
+};
+
+class mainTrack: public ::xml_schema::type
+{
+  public:
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // dir
+  //
+  typedef ::dir dir_type;
+  typedef ::xsd::cxx::tree::optional< dir_type > dir_optional;
+  typedef ::xsd::cxx::tree::traits< dir_type, char > dir_traits;
+
+  const dir_optional&
+  dir () const;
+
+  dir_optional&
+  dir ();
+
+  void
+  dir (const dir_type& x);
+
+  void
+  dir (const dir_optional& x);
+
+  void
+  dir (::std::unique_ptr< dir_type > p);
+
+  // Constructors.
+  //
+  mainTrack ();
+
+  mainTrack (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  mainTrack (const mainTrack& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual mainTrack*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  mainTrack&
+  operator= (const mainTrack& x);
+
+  virtual 
+  ~mainTrack ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  id_optional id_;
+  s_optional s_;
+  dir_optional dir_;
+};
+
+class sideTrack: public ::xml_schema::type
+{
+  public:
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // dir
+  //
+  typedef ::dir dir_type;
+  typedef ::xsd::cxx::tree::optional< dir_type > dir_optional;
+  typedef ::xsd::cxx::tree::traits< dir_type, char > dir_traits;
+
+  const dir_optional&
+  dir () const;
+
+  dir_optional&
+  dir ();
+
+  void
+  dir (const dir_type& x);
+
+  void
+  dir (const dir_optional& x);
+
+  void
+  dir (::std::unique_ptr< dir_type > p);
+
+  // Constructors.
+  //
+  sideTrack ();
+
+  sideTrack (const ::xercesc::DOMElement& e,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  sideTrack (const sideTrack& x,
+             ::xml_schema::flags f = 0,
+             ::xml_schema::container* c = 0);
+
+  virtual sideTrack*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  sideTrack&
+  operator= (const sideTrack& x);
+
+  virtual 
+  ~sideTrack ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  id_optional id_;
+  s_optional s_;
+  dir_optional dir_;
+};
+
+class partner: public ::xml_schema::type
+{
+  public:
+  // name
+  //
+  typedef ::xml_schema::string name_type;
+  typedef ::xsd::cxx::tree::optional< name_type > name_optional;
+  typedef ::xsd::cxx::tree::traits< name_type, char > name_traits;
+
+  const name_optional&
+  name () const;
+
+  name_optional&
+  name ();
+
+  void
+  name (const name_type& x);
+
+  void
+  name (const name_optional& x);
+
+  void
+  name (::std::unique_ptr< name_type > p);
+
+  // id
+  //
+  typedef ::xml_schema::string id_type;
+  typedef ::xsd::cxx::tree::optional< id_type > id_optional;
+  typedef ::xsd::cxx::tree::traits< id_type, char > id_traits;
+
+  const id_optional&
+  id () const;
+
+  id_optional&
+  id ();
+
+  void
+  id (const id_type& x);
+
+  void
+  id (const id_optional& x);
+
+  void
+  id (::std::unique_ptr< id_type > p);
+
+  // Constructors.
+  //
+  partner ();
+
+  partner (const ::xercesc::DOMElement& e,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  partner (const partner& x,
+           ::xml_schema::flags f = 0,
+           ::xml_schema::container* c = 0);
+
+  virtual partner*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  partner&
+  operator= (const partner& x);
+
+  virtual 
+  ~partner ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  name_optional name_;
+  id_optional id_;
+};
+
+class cornerRoad: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // s
+  //
+  typedef ::xml_schema::double_ s_type;
+  typedef ::xsd::cxx::tree::optional< s_type > s_optional;
+  typedef ::xsd::cxx::tree::traits< s_type, char, ::xsd::cxx::tree::schema_type::double_ > s_traits;
+
+  const s_optional&
+  s () const;
+
+  s_optional&
+  s ();
+
+  void
+  s (const s_type& x);
+
+  void
+  s (const s_optional& x);
+
+  // t
+  //
+  typedef ::xml_schema::double_ t_type;
+  typedef ::xsd::cxx::tree::optional< t_type > t_optional;
+  typedef ::xsd::cxx::tree::traits< t_type, char, ::xsd::cxx::tree::schema_type::double_ > t_traits;
+
+  const t_optional&
+  t () const;
+
+  t_optional&
+  t ();
+
+  void
+  t (const t_type& x);
+
+  void
+  t (const t_optional& x);
+
+  // dz
+  //
+  typedef ::xml_schema::double_ dz_type;
+  typedef ::xsd::cxx::tree::optional< dz_type > dz_optional;
+  typedef ::xsd::cxx::tree::traits< dz_type, char, ::xsd::cxx::tree::schema_type::double_ > dz_traits;
+
+  const dz_optional&
+  dz () const;
+
+  dz_optional&
+  dz ();
+
+  void
+  dz (const dz_type& x);
+
+  void
+  dz (const dz_optional& x);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // Constructors.
+  //
+  cornerRoad ();
+
+  cornerRoad (const ::xercesc::DOMElement& e,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  cornerRoad (const cornerRoad& x,
+              ::xml_schema::flags f = 0,
+              ::xml_schema::container* c = 0);
+
+  virtual cornerRoad*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  cornerRoad&
+  operator= (const cornerRoad& x);
+
+  virtual 
+  ~cornerRoad ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  s_optional s_;
+  t_optional t_;
+  dz_optional dz_;
+  height_optional height_;
+};
+
+class cornerLocal: public ::xml_schema::type
+{
+  public:
+  // userData
+  //
+  typedef ::userData userData_type;
+  typedef ::xsd::cxx::tree::sequence< userData_type > userData_sequence;
+  typedef userData_sequence::iterator userData_iterator;
+  typedef userData_sequence::const_iterator userData_const_iterator;
+  typedef ::xsd::cxx::tree::traits< userData_type, char > userData_traits;
+
+  const userData_sequence&
+  userData () const;
+
+  userData_sequence&
+  userData ();
+
+  void
+  userData (const userData_sequence& s);
+
+  // include
+  //
+  typedef ::include include_type;
+  typedef ::xsd::cxx::tree::sequence< include_type > include_sequence;
+  typedef include_sequence::iterator include_iterator;
+  typedef include_sequence::const_iterator include_const_iterator;
+  typedef ::xsd::cxx::tree::traits< include_type, char > include_traits;
+
+  const include_sequence&
+  include () const;
+
+  include_sequence&
+  include ();
+
+  void
+  include (const include_sequence& s);
+
+  // u
+  //
+  typedef ::xml_schema::double_ u_type;
+  typedef ::xsd::cxx::tree::optional< u_type > u_optional;
+  typedef ::xsd::cxx::tree::traits< u_type, char, ::xsd::cxx::tree::schema_type::double_ > u_traits;
+
+  const u_optional&
+  u () const;
+
+  u_optional&
+  u ();
+
+  void
+  u (const u_type& x);
+
+  void
+  u (const u_optional& x);
+
+  // v
+  //
+  typedef ::xml_schema::double_ v_type;
+  typedef ::xsd::cxx::tree::optional< v_type > v_optional;
+  typedef ::xsd::cxx::tree::traits< v_type, char, ::xsd::cxx::tree::schema_type::double_ > v_traits;
+
+  const v_optional&
+  v () const;
+
+  v_optional&
+  v ();
+
+  void
+  v (const v_type& x);
+
+  void
+  v (const v_optional& x);
+
+  // z
+  //
+  typedef ::xml_schema::double_ z_type;
+  typedef ::xsd::cxx::tree::optional< z_type > z_optional;
+  typedef ::xsd::cxx::tree::traits< z_type, char, ::xsd::cxx::tree::schema_type::double_ > z_traits;
+
+  const z_optional&
+  z () const;
+
+  z_optional&
+  z ();
+
+  void
+  z (const z_type& x);
+
+  void
+  z (const z_optional& x);
+
+  // height
+  //
+  typedef ::xml_schema::double_ height_type;
+  typedef ::xsd::cxx::tree::optional< height_type > height_optional;
+  typedef ::xsd::cxx::tree::traits< height_type, char, ::xsd::cxx::tree::schema_type::double_ > height_traits;
+
+  const height_optional&
+  height () const;
+
+  height_optional&
+  height ();
+
+  void
+  height (const height_type& x);
+
+  void
+  height (const height_optional& x);
+
+  // Constructors.
+  //
+  cornerLocal ();
+
+  cornerLocal (const ::xercesc::DOMElement& e,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  cornerLocal (const cornerLocal& x,
+               ::xml_schema::flags f = 0,
+               ::xml_schema::container* c = 0);
+
+  virtual cornerLocal*
+  _clone (::xml_schema::flags f = 0,
+          ::xml_schema::container* c = 0) const;
+
+  cornerLocal&
+  operator= (const cornerLocal& x);
+
+  virtual 
+  ~cornerLocal ();
+
+  // Implementation.
+  //
+  protected:
+  void
+  parse (::xsd::cxx::xml::dom::parser< char >&,
+         ::xml_schema::flags);
+
+  protected:
+  userData_sequence userData_;
+  include_sequence include_;
+  u_optional u_;
+  v_optional v_;
+  z_optional z_;
+  height_optional height_;
+};
+
+#include <iosfwd>
+
+#include <xercesc/sax/InputSource.hpp>
+#include <xercesc/dom/DOMDocument.hpp>
+#include <xercesc/dom/DOMErrorHandler.hpp>
+
+// Parse a URI or a local file.
+//
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& uri,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& uri,
+            ::xml_schema::error_handler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::std::string& uri,
+            ::xercesc::DOMErrorHandler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+// Parse std::istream.
+//
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xml_schema::error_handler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            ::xercesc::DOMErrorHandler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& id,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& id,
+            ::xml_schema::error_handler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::std::istream& is,
+            const ::std::string& id,
+            ::xercesc::DOMErrorHandler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+// Parse xercesc::InputSource.
+//
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& is,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& is,
+            ::xml_schema::error_handler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xercesc::InputSource& is,
+            ::xercesc::DOMErrorHandler& eh,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+// Parse xercesc::DOMDocument.
+//
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (const ::xercesc::DOMDocument& d,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+::std::unique_ptr< ::OpenDRIVE >
+OpenDRIVE_ (::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument > d,
+            ::xml_schema::flags f = 0,
+            const ::xml_schema::properties& p = ::xml_schema::properties ());
+
+#include <iosfwd>
+
+#include <xercesc/dom/DOMDocument.hpp>
+#include <xercesc/dom/DOMErrorHandler.hpp>
+#include <xercesc/framework/XMLFormatter.hpp>
+
+#include <xsd/cxx/xml/dom/auto-ptr.hxx>
+
+// Serialize to std::ostream.
+//
+
+void
+OpenDRIVE_ (::std::ostream& os,
+            const ::OpenDRIVE& x, 
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+void
+OpenDRIVE_ (::std::ostream& os,
+            const ::OpenDRIVE& x, 
+            ::xml_schema::error_handler& eh,
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+void
+OpenDRIVE_ (::std::ostream& os,
+            const ::OpenDRIVE& x, 
+            ::xercesc::DOMErrorHandler& eh,
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+// Serialize to xercesc::XMLFormatTarget.
+//
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& ft,
+            const ::OpenDRIVE& x, 
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& ft,
+            const ::OpenDRIVE& x, 
+            ::xml_schema::error_handler& eh,
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+void
+OpenDRIVE_ (::xercesc::XMLFormatTarget& ft,
+            const ::OpenDRIVE& x, 
+            ::xercesc::DOMErrorHandler& eh,
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            const ::std::string& e = "UTF-8",
+            ::xml_schema::flags f = 0);
+
+// Serialize to an existing xercesc::DOMDocument.
+//
+
+void
+OpenDRIVE_ (::xercesc::DOMDocument& d,
+            const ::OpenDRIVE& x,
+            ::xml_schema::flags f = 0);
+
+// Serialize to a new xercesc::DOMDocument.
+//
+
+::xml_schema::dom::unique_ptr< ::xercesc::DOMDocument >
+OpenDRIVE_ (const ::OpenDRIVE& x, 
+            const ::xml_schema::namespace_infomap& m = ::xml_schema::namespace_infomap (),
+            ::xml_schema::flags f = 0);
+
+void
+operator<< (::xercesc::DOMElement&, const elementType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const elementType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const elementType&);
+
+void
+operator<< (::xercesc::DOMElement&, const max&);
+
+void
+operator<< (::xercesc::DOMAttr&, const max&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const max&);
+
+void
+operator<< (::xercesc::DOMElement&, const contactPoint&);
+
+void
+operator<< (::xercesc::DOMAttr&, const contactPoint&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const contactPoint&);
+
+void
+operator<< (::xercesc::DOMElement&, const side&);
+
+void
+operator<< (::xercesc::DOMAttr&, const side&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const side&);
+
+void
+operator<< (::xercesc::DOMElement&, const direction&);
+
+void
+operator<< (::xercesc::DOMAttr&, const direction&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const direction&);
+
+void
+operator<< (::xercesc::DOMElement&, const roadType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const roadType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const roadType&);
+
+void
+operator<< (::xercesc::DOMElement&, const unit&);
+
+void
+operator<< (::xercesc::DOMAttr&, const unit&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const unit&);
+
+void
+operator<< (::xercesc::DOMElement&, const pRange&);
+
+void
+operator<< (::xercesc::DOMAttr&, const pRange&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const pRange&);
+
+void
+operator<< (::xercesc::DOMElement&, const crossfallSide&);
+
+void
+operator<< (::xercesc::DOMAttr&, const crossfallSide&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const crossfallSide&);
+
+void
+operator<< (::xercesc::DOMElement&, const singleSide&);
+
+void
+operator<< (::xercesc::DOMAttr&, const singleSide&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const singleSide&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const laneType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const laneType&);
+
+void
+operator<< (::xercesc::DOMElement&, const roadmarkType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const roadmarkType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const roadmarkType&);
+
+void
+operator<< (::xercesc::DOMElement&, const weight&);
+
+void
+operator<< (::xercesc::DOMAttr&, const weight&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const weight&);
+
+void
+operator<< (::xercesc::DOMElement&, const color&);
+
+void
+operator<< (::xercesc::DOMAttr&, const color&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const color&);
+
+void
+operator<< (::xercesc::DOMElement&, const restriction&);
+
+void
+operator<< (::xercesc::DOMAttr&, const restriction&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const restriction&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneChange&);
+
+void
+operator<< (::xercesc::DOMAttr&, const laneChange&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const laneChange&);
+
+void
+operator<< (::xercesc::DOMElement&, const rule&);
+
+void
+operator<< (::xercesc::DOMAttr&, const rule&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const rule&);
+
+void
+operator<< (::xercesc::DOMElement&, const orientation&);
+
+void
+operator<< (::xercesc::DOMAttr&, const orientation&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const orientation&);
+
+void
+operator<< (::xercesc::DOMElement&, const tunnelType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const tunnelType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const tunnelType&);
+
+void
+operator<< (::xercesc::DOMElement&, const bridgeType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const bridgeType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const bridgeType&);
+
+void
+operator<< (::xercesc::DOMElement&, const parkingSpace_access&);
+
+void
+operator<< (::xercesc::DOMAttr&, const parkingSpace_access&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const parkingSpace_access&);
+
+void
+operator<< (::xercesc::DOMElement&, const parkingSpacemarkingSide&);
+
+void
+operator<< (::xercesc::DOMAttr&, const parkingSpacemarkingSide&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const parkingSpacemarkingSide&);
+
+void
+operator<< (::xercesc::DOMElement&, const dynamic&);
+
+void
+operator<< (::xercesc::DOMAttr&, const dynamic&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const dynamic&);
+
+void
+operator<< (::xercesc::DOMElement&, const surfaceOrientation&);
+
+void
+operator<< (::xercesc::DOMAttr&, const surfaceOrientation&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const surfaceOrientation&);
+
+void
+operator<< (::xercesc::DOMElement&, const mode&);
+
+void
+operator<< (::xercesc::DOMAttr&, const mode&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const mode&);
+
+void
+operator<< (::xercesc::DOMElement&, const purpose&);
+
+void
+operator<< (::xercesc::DOMAttr&, const purpose&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const purpose&);
+
+void
+operator<< (::xercesc::DOMElement&, const position&);
+
+void
+operator<< (::xercesc::DOMAttr&, const position&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const position&);
+
+void
+operator<< (::xercesc::DOMElement&, const dir&);
+
+void
+operator<< (::xercesc::DOMAttr&, const dir&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const dir&);
+
+void
+operator<< (::xercesc::DOMElement&, const junctionGroupType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const junctionGroupType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const junctionGroupType&);
+
+void
+operator<< (::xercesc::DOMElement&, const stationType&);
+
+void
+operator<< (::xercesc::DOMAttr&, const stationType&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const stationType&);
+
+void
+operator<< (::xercesc::DOMElement&, const userData&);
+
+void
+operator<< (::xercesc::DOMElement&, const include&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneValidity&);
+
+void
+operator<< (::xercesc::DOMElement&, const parkingSpace&);
+
+void
+operator<< (::xercesc::DOMElement&, const lane&);
+
+void
+operator<< (::xercesc::DOMElement&, const centerLane&);
+
+void
+operator<< (::xercesc::DOMElement&, const OpenDRIVE&);
+
+void
+operator<< (::xercesc::DOMElement&, const max_member&);
+
+void
+operator<< (::xercesc::DOMAttr&, const max_member&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const max_member&);
+
+void
+operator<< (::xercesc::DOMElement&, const max_member1&);
+
+void
+operator<< (::xercesc::DOMAttr&, const max_member1&);
+
+void
+operator<< (::xml_schema::list_stream&,
+            const max_member1&);
+
+void
+operator<< (::xercesc::DOMElement&, const marking&);
+
+void
+operator<< (::xercesc::DOMElement&, const lane_link&);
+
+void
+operator<< (::xercesc::DOMElement&, const width&);
+
+void
+operator<< (::xercesc::DOMElement&, const border&);
+
+void
+operator<< (::xercesc::DOMElement&, const roadMark&);
+
+void
+operator<< (::xercesc::DOMElement&, const material&);
+
+void
+operator<< (::xercesc::DOMElement&, const visibility&);
+
+void
+operator<< (::xercesc::DOMElement&, const speed&);
+
+void
+operator<< (::xercesc::DOMElement&, const access1&);
+
+void
+operator<< (::xercesc::DOMElement&, const height&);
+
+void
+operator<< (::xercesc::DOMElement&, const rule1&);
+
+void
+operator<< (::xercesc::DOMElement&, const link1&);
+
+void
+operator<< (::xercesc::DOMElement&, const roadMark1&);
+
+void
+operator<< (::xercesc::DOMElement&, const header&);
+
+void
+operator<< (::xercesc::DOMElement&, const road&);
+
+void
+operator<< (::xercesc::DOMElement&, const controller&);
+
+void
+operator<< (::xercesc::DOMElement&, const junction&);
+
+void
+operator<< (::xercesc::DOMElement&, const junctionGroup&);
+
+void
+operator<< (::xercesc::DOMElement&, const station&);
+
+void
+operator<< (::xercesc::DOMElement&, const predecessor&);
+
+void
+operator<< (::xercesc::DOMElement&, const successor&);
+
+void
+operator<< (::xercesc::DOMElement&, const type&);
+
+void
+operator<< (::xercesc::DOMElement&, const type1&);
+
+void
+operator<< (::xercesc::DOMElement&, const link2&);
+
+void
+operator<< (::xercesc::DOMElement&, const type2&);
+
+void
+operator<< (::xercesc::DOMElement&, const planView&);
+
+void
+operator<< (::xercesc::DOMElement&, const elevationProfile&);
+
+void
+operator<< (::xercesc::DOMElement&, const lateralProfile&);
+
+void
+operator<< (::xercesc::DOMElement&, const lanes&);
+
+void
+operator<< (::xercesc::DOMElement&, const objects&);
+
+void
+operator<< (::xercesc::DOMElement&, const signals&);
+
+void
+operator<< (::xercesc::DOMElement&, const surface&);
+
+void
+operator<< (::xercesc::DOMElement&, const railroad&);
+
+void
+operator<< (::xercesc::DOMElement&, const control&);
+
+void
+operator<< (::xercesc::DOMElement&, const connection&);
+
+void
+operator<< (::xercesc::DOMElement&, const priority&);
+
+void
+operator<< (::xercesc::DOMElement&, const controller1&);
+
+void
+operator<< (::xercesc::DOMElement&, const junctionReference&);
+
+void
+operator<< (::xercesc::DOMElement&, const platform&);
+
+void
+operator<< (::xercesc::DOMElement&, const line&);
+
+void
+operator<< (::xercesc::DOMElement&, const predecessor1&);
+
+void
+operator<< (::xercesc::DOMElement&, const successor1&);
+
+void
+operator<< (::xercesc::DOMElement&, const neighbor&);
+
+void
+operator<< (::xercesc::DOMElement&, const speed1&);
+
+void
+operator<< (::xercesc::DOMElement&, const geometry&);
+
+void
+operator<< (::xercesc::DOMElement&, const elevation&);
+
+void
+operator<< (::xercesc::DOMElement&, const superelevation&);
+
+void
+operator<< (::xercesc::DOMElement&, const crossfall&);
+
+void
+operator<< (::xercesc::DOMElement&, const shape&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneOffset&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneSection&);
+
+void
+operator<< (::xercesc::DOMElement&, const object&);
+
+void
+operator<< (::xercesc::DOMElement&, const objectReference&);
+
+void
+operator<< (::xercesc::DOMElement&, const tunnel&);
+
+void
+operator<< (::xercesc::DOMElement&, const bridge&);
+
+void
+operator<< (::xercesc::DOMElement&, const signal&);
+
+void
+operator<< (::xercesc::DOMElement&, const signalReference&);
+
+void
+operator<< (::xercesc::DOMElement&, const CRG&);
+
+void
+operator<< (::xercesc::DOMElement&, const switch_&);
+
+void
+operator<< (::xercesc::DOMElement&, const laneLink&);
+
+void
+operator<< (::xercesc::DOMElement&, const segment&);
+
+void
+operator<< (::xercesc::DOMElement&, const line1&);
+
+void
+operator<< (::xercesc::DOMElement&, const spiral&);
+
+void
+operator<< (::xercesc::DOMElement&, const arc&);
+
+void
+operator<< (::xercesc::DOMElement&, const poly3&);
+
+void
+operator<< (::xercesc::DOMElement&, const paramPoly3&);
+
+void
+operator<< (::xercesc::DOMElement&, const left&);
+
+void
+operator<< (::xercesc::DOMElement&, const center&);
+
+void
+operator<< (::xercesc::DOMElement&, const right&);
+
+void
+operator<< (::xercesc::DOMElement&, const repeat&);
+
+void
+operator<< (::xercesc::DOMElement&, const outline&);
+
+void
+operator<< (::xercesc::DOMElement&, const material1&);
+
+void
+operator<< (::xercesc::DOMElement&, const dependency&);
+
+void
+operator<< (::xercesc::DOMElement&, const mainTrack&);
+
+void
+operator<< (::xercesc::DOMElement&, const sideTrack&);
+
+void
+operator<< (::xercesc::DOMElement&, const partner&);
+
+void
+operator<< (::xercesc::DOMElement&, const cornerRoad&);
+
+void
+operator<< (::xercesc::DOMElement&, const cornerLocal&);
+
+#include <xsd/cxx/post.hxx>
+
+// Begin epilogue.
+//
+//
+// End epilogue.
+
+#endif // OPEN_DRIVE_1_4H_HXX
diff --git a/src/xml/OpenDRIVE_1.4H.xsd b/src/xml/OpenDRIVE_1.4H.xsd
new file mode 100644
index 0000000..13cb398
--- /dev/null
+++ b/src/xml/OpenDRIVE_1.4H.xsd
@@ -0,0 +1,1284 @@
+<?xml version="1.0"?>
+<xsd:schema xmlns:xsd="http://www.w3.org/2001/XMLSchema">
+
+<xsd:annotation>
+    <xsd:documentation>
+    XML Schema Definition for OpenDRIVE XML files - Rev. 1.4H, excluding SET records, (c)2015 by VIRES Simulationstechnologie GmbH, Germany
+    </xsd:documentation>
+</xsd:annotation>
+
+
+<xsd:element name="OpenDRIVE">
+    <xsd:complexType>
+        <xsd:sequence>
+        <xsd:element name="header">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="geoReference" type="xsd:string" minOccurs="0" maxOccurs="1"/>
+                    <xsd:element name="userData"     type="userData"   minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"      type="include"    minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="revMajor" type="xsd:unsignedShort"/>
+                <xsd:attribute name="revMinor" type="xsd:unsignedShort"/>
+                <xsd:attribute name="name"     type="xsd:string"/>
+                <xsd:attribute name="version"  type="xsd:float"/>
+                <xsd:attribute name="date"     type="xsd:string"/>
+                <xsd:attribute name="north"    type="xsd:double"/>
+                <xsd:attribute name="south"    type="xsd:double"/>
+                <xsd:attribute name="east"     type="xsd:double"/>
+                <xsd:attribute name="west"     type="xsd:double"/>
+                <xsd:attribute name="vendor"   type="xsd:string"/>
+            </xsd:complexType>
+        </xsd:element>         
+    <xsd:element name="road" maxOccurs="unbounded">
+    <xsd:complexType>            
+        <xsd:sequence>
+                <xsd:element name="link" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="predecessor" minOccurs="0" maxOccurs="1">                            
+                                <xsd:complexType>                              
+                                    <xsd:attribute name="elementType"  type="elementType"/>                                                              
+                                     <xsd:attribute name="elementId"    type="xsd:string"/>
+                                    <xsd:attribute name="contactPoint" type="contactPoint"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="successor" minOccurs="0" maxOccurs="1">
+                                <xsd:complexType>                     
+                                    <xsd:attribute name="elementType"  type="elementType"/>                                                                      
+                                    <xsd:attribute name="elementId"    type="xsd:string"/>
+                                    <xsd:attribute name="contactPoint" type="contactPoint"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="neighbor" minOccurs="0" maxOccurs="2">                          
+                                <xsd:complexType>                               
+                                    <xsd:attribute name="side"      type="side"/>                                                              
+                                    <xsd:attribute name="elementId" type="xsd:string"/>
+                                    <xsd:attribute name="direction" type="direction"/>                                    
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element>
+                <xsd:element name="type" minOccurs="0" maxOccurs="unbounded">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="speed" minOccurs="0" maxOccurs="1">
+                                <xsd:complexType>
+                                    <xsd:attribute name="max"  type="max"/>
+                                    <xsd:attribute name="unit" type="unit"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include" type="include"   minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                        <xsd:attribute name="s"    type="xsd:double"/>
+                        <xsd:attribute name="type" type="roadType"/>
+                    </xsd:complexType>
+                </xsd:element>
+                
+                <xsd:element name="planView" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="geometry" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:choice>
+                                        <xsd:element name="line">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="spiral">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="curvStart" type="xsd:double"/>
+                                                <xsd:attribute name="curvEnd"   type="xsd:double"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="arc">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="curvature" type="xsd:double"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="poly3">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="a" type="xsd:double"/>
+                                                <xsd:attribute name="b" type="xsd:double"/>
+                                                <xsd:attribute name="c" type="xsd:double"/>
+                                                <xsd:attribute name="d" type="xsd:double"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="paramPoly3">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="aU"     type="xsd:double"/>
+                                                <xsd:attribute name="bU"     type="xsd:double"/>
+                                                <xsd:attribute name="cU"     type="xsd:double"/>
+                                                <xsd:attribute name="dU"     type="xsd:double"/>
+                                                <xsd:attribute name="aV"     type="xsd:double"/>
+                                                <xsd:attribute name="bV"     type="xsd:double"/>
+                                                <xsd:attribute name="cV"     type="xsd:double"/>
+                                                <xsd:attribute name="dV"     type="xsd:double"/>
+                                                <xsd:attribute name="pRange" type="pRange"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:choice>
+                                    <xsd:attribute name="s"      type="xsd:double"/>
+                                    <xsd:attribute name="x"      type="xsd:double"/>
+                                    <xsd:attribute name="y"      type="xsd:double"/>
+                                    <xsd:attribute name="hdg"    type="xsd:double"/>
+                                    <xsd:attribute name="length" type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end planView -->
+                
+                <xsd:element name="elevationProfile" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                             <xsd:element name="elevation" minOccurs="1" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s" type="xsd:double"/>
+                                    <xsd:attribute name="a" type="xsd:double"/>
+                                    <xsd:attribute name="b" type="xsd:double"/>
+                                    <xsd:attribute name="c" type="xsd:double"/>
+                                    <xsd:attribute name="d" type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element>
+                <xsd:element name="lateralProfile" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="superelevation" minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s" type="xsd:double"/>
+                                    <xsd:attribute name="a" type="xsd:double"/>
+                                    <xsd:attribute name="b" type="xsd:double"/>
+                                    <xsd:attribute name="c" type="xsd:double"/>
+                                    <xsd:attribute name="d" type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="crossfall" minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="side" type="crossfallSide"/>
+                                    <xsd:attribute name="s"    type="xsd:double"/>
+                                    <xsd:attribute name="a"    type="xsd:double"/>
+                                    <xsd:attribute name="b"    type="xsd:double"/>
+                                    <xsd:attribute name="c"    type="xsd:double"/>
+                                    <xsd:attribute name="d"    type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="shape" minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s" type="xsd:double"/>
+                                    <xsd:attribute name="t" type="xsd:double"/>
+                                    <xsd:attribute name="a" type="xsd:double"/>
+                                    <xsd:attribute name="b" type="xsd:double"/>
+                                    <xsd:attribute name="c" type="xsd:double"/>
+                                    <xsd:attribute name="d" type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element>
+                
+                <xsd:element name="lanes" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="laneOffset" minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"    type="xsd:double"/>
+                                    <xsd:attribute name="a"    type="xsd:double"/>
+                                    <xsd:attribute name="b"    type="xsd:double"/>
+                                    <xsd:attribute name="c"    type="xsd:double"/>
+                                    <xsd:attribute name="d"    type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end laneOffset -->
+                            <xsd:element name="laneSection" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="left" minOccurs="0" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="lane"     type="lane"     maxOccurs="unbounded"/>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="center" minOccurs="1" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="lane"     type="centerLane" minOccurs="0" maxOccurs="1"/>
+                                                    <xsd:element name="userData" type="userData"   minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"    minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="right" minOccurs="0" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="lane"     type="lane"     maxOccurs="unbounded"/>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"          type="xsd:double"/>
+                                    <xsd:attribute name="singleSide" type="singleSide"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end laneSection -->
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end lanes -->
+                
+                <xsd:element name="objects" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="object"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="repeat" minOccurs="0" maxOccurs="unbounded">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="s"            type="xsd:double"/>
+                                                <xsd:attribute name="length"       type="xsd:double"/>
+                                                <xsd:attribute name="distance"     type="xsd:double"/>
+                                                <xsd:attribute name="tStart"       type="xsd:double"/>
+                                                <xsd:attribute name="tEnd"         type="xsd:double"/>
+                                                <xsd:attribute name="widthStart"   type="xsd:double"/>
+                                                <xsd:attribute name="widthEnd"     type="xsd:double"/>
+                                                <xsd:attribute name="heightStart"  type="xsd:double"/>
+                                                <xsd:attribute name="heightEnd"    type="xsd:double"/>
+                                                <xsd:attribute name="zOffsetStart" type="xsd:double"/>
+                                                <xsd:attribute name="zOffsetEnd"   type="xsd:double"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="outline"  minOccurs="0" maxOccurs="1">
+                                            <xsd:complexType>					    
+                                                <xsd:sequence>
+						  <xsd:choice>
+                                                    <xsd:element name="cornerRoad" minOccurs="0" maxOccurs="unbounded">
+                                                        <xsd:complexType>
+                                                            <xsd:sequence>
+                                                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                            </xsd:sequence>
+                                                            <xsd:attribute name="s"      type="xsd:double"/>
+                                                            <xsd:attribute name="t"      type="xsd:double"/>
+                                                            <xsd:attribute name="dz"     type="xsd:double"/>
+                                                            <xsd:attribute name="height" type="xsd:double"/>
+                                                        </xsd:complexType>
+                                                    </xsd:element>
+                                                    <xsd:element name="cornerLocal" minOccurs="0" maxOccurs="unbounded">
+                                                        <xsd:complexType>
+                                                            <xsd:sequence>
+                                                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                            </xsd:sequence>
+                                                            <xsd:attribute name="u"      type="xsd:double"/>
+                                                            <xsd:attribute name="v"      type="xsd:double"/>
+                                                            <xsd:attribute name="z"      type="xsd:double"/>
+                                                            <xsd:attribute name="height" type="xsd:double"/>
+                                                        </xsd:complexType>
+                                                    </xsd:element>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                    </xsd:choice>
+						    </xsd:sequence>						
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="material" minOccurs="0" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="surface"   type="xsd:string"/>
+                                                <xsd:attribute name="friction"  type="xsd:double"/>
+                                                <xsd:attribute name="roughness" type="xsd:double"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="validity"     type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="parkingSpace" type="parkingSpace" minOccurs="0" maxOccurs="1"/>
+                                        <xsd:element name="userData"     type="userData"     minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"      type="include"      minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="type"        type="xsd:string"/>
+                                    <xsd:attribute name="name"        type="xsd:string"/>
+                                    <xsd:attribute name="id"          type="xsd:string"/>
+                                    <xsd:attribute name="s"           type="xsd:double"/>
+                                    <xsd:attribute name="t"           type="xsd:double"/>
+                                    <xsd:attribute name="zOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="validLength" type="xsd:double"/>
+                                    <xsd:attribute name="orientation" type="orientation"/>
+                                    <xsd:attribute name="length"      type="xsd:double"/>
+                                    <xsd:attribute name="width"       type="xsd:double"/>
+                                    <xsd:attribute name="radius"      type="xsd:double"/>
+                                    <xsd:attribute name="height"      type="xsd:double"/>
+                                    <xsd:attribute name="hdg"         type="xsd:double"/>
+                                    <xsd:attribute name="pitch"       type="xsd:double"/>
+                                    <xsd:attribute name="roll"        type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="objectReference"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="validity" type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="userData" type="userData"     minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"      minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"           type="xsd:double"/>
+                                    <xsd:attribute name="t"           type="xsd:double"/>
+                                    <xsd:attribute name="id"          type="xsd:string"/>
+                                    <xsd:attribute name="zOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="validLength" type="xsd:double"/>
+                                    <xsd:attribute name="orientation" type="orientation"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="tunnel"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="validity" type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="userData" type="userData"     minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"      minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"        type="xsd:double"/>
+                                    <xsd:attribute name="length"   type="xsd:double"/>
+                                    <xsd:attribute name="name"     type="xsd:string"/>
+                                    <xsd:attribute name="id"       type="xsd:string"/>
+                                    <xsd:attribute name="type"     type="tunnelType"/>
+                                    <xsd:attribute name="lighting" type="xsd:double"/>
+                                    <xsd:attribute name="daylight" type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="bridge"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="validity" type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="userData" type="userData"     minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"      minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"      type="xsd:double"/>
+                                    <xsd:attribute name="length" type="xsd:double"/>
+                                    <xsd:attribute name="name"   type="xsd:string"/>
+                                    <xsd:attribute name="id"     type="xsd:string"/>
+                                    <xsd:attribute name="type"   type="bridgeType"/>
+                                </xsd:complexType>
+                            </xsd:element>
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end objects -->
+
+                <xsd:element name="signals" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="signal"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="validity" type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="dependency" minOccurs="0" maxOccurs="unbounded">
+                                            <xsd:complexType>
+                                                <xsd:sequence>
+                                                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                                </xsd:sequence>
+                                                <xsd:attribute name="id"   type="xsd:string"/>
+                                                <xsd:attribute name="type" type="xsd:string"/>
+                                            </xsd:complexType>
+                                        </xsd:element>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"           type="xsd:double"/>
+                                    <xsd:attribute name="t"           type="xsd:double"/>
+                                    <xsd:attribute name="id"          type="xsd:string"/>
+                                    <xsd:attribute name="name"        type="xsd:string"/>
+                                    <xsd:attribute name="dynamic"     type="dynamic"/>
+                                    <xsd:attribute name="orientation" type="orientation"/>
+                                    <xsd:attribute name="zOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="country"     type="xsd:string"/>
+                                    <xsd:attribute name="type"        type="xsd:string"/>
+                                    <xsd:attribute name="subtype"     type="xsd:string"/>
+                                    <xsd:attribute name="value"       type="xsd:double"/>
+                                    <xsd:attribute name="unit"        type="unit"/>
+                                    <xsd:attribute name="height"      type="xsd:double"/>
+                                    <xsd:attribute name="width"       type="xsd:double"/>
+                                    <xsd:attribute name="text"        type="xsd:string"/>
+                                    <xsd:attribute name="hOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="pitch"       type="xsd:double"/>
+                                    <xsd:attribute name="roll"        type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end signal -->
+                            <xsd:element name="signalReference"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="validity" type="laneValidity" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="s"           type="xsd:double"/>
+                                    <xsd:attribute name="t"           type="xsd:double"/>
+                                    <xsd:attribute name="id"          type="xsd:string"/>
+                                    <xsd:attribute name="orientation" type="orientation"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end signal reference -->
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end signals -->
+                
+                <xsd:element name="surface" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="CRG"  minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="file"        type="xsd:string"/>
+                                    <xsd:attribute name="sStart"      type="xsd:double"/>
+                                    <xsd:attribute name="sEnd"        type="xsd:double"/>
+                                    <xsd:attribute name="orientation" type="surfaceOrientation"/>
+                                    <xsd:attribute name="mode"        type="mode"/>
+                                    <xsd:attribute name="purpose"     type="purpose"/>
+                                    <xsd:attribute name="sOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="tOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="zOffset"     type="xsd:double"/>
+                                    <xsd:attribute name="zScale"      type="xsd:double"/>
+                                    <xsd:attribute name="hOffset"     type="xsd:double"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end CRG -->
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end surface -->
+                <xsd:element name="railroad" minOccurs="0" maxOccurs="1">
+                    <xsd:complexType>
+                        <xsd:sequence>
+                            <xsd:element name="switch" minOccurs="0" maxOccurs="unbounded">
+                                <xsd:complexType>
+                                    <xsd:sequence>
+                                        <xsd:element name="mainTrack" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:attribute name="id"  type="xsd:string"/>
+                                                <xsd:attribute name="s"   type="xsd:double"/>
+                                                <xsd:attribute name="dir" type="dir"/>
+                                            </xsd:complexType>
+                                        </xsd:element> <!-- end mainTrack -->
+                                        <xsd:element name="sideTrack" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:attribute name="id"  type="xsd:string"/>
+                                                <xsd:attribute name="s"   type="xsd:double"/>
+                                                <xsd:attribute name="dir" type="dir"/>
+                                            </xsd:complexType>
+                                        </xsd:element> <!-- end sideTrack -->
+                                        <xsd:element name="partner" minOccurs="0" maxOccurs="1">
+                                            <xsd:complexType>
+                                                <xsd:attribute name="name" type="xsd:string"/>
+                                                <xsd:attribute name="id"   type="xsd:string"/>
+                                            </xsd:complexType>
+                                        </xsd:element> <!-- end partner -->
+                                        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                    </xsd:sequence>
+                                    <xsd:attribute name="name"     type="xsd:string"/>
+                                    <xsd:attribute name="id"       type="xsd:string"/>
+                                    <xsd:attribute name="position" type="position"/>
+                                </xsd:complexType>
+                            </xsd:element> <!-- end switch -->
+                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                        </xsd:sequence>
+                    </xsd:complexType>
+                </xsd:element> <!-- end railroad -->
+                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="name"     type="xsd:string"/>
+                <xsd:attribute name="length"   type="xsd:double"/>
+                <xsd:attribute name="id"       type="xsd:string"/>
+                <xsd:attribute name="junction" type="xsd:string"/>
+            </xsd:complexType> <!-- end road -->
+        </xsd:element>
+
+        <xsd:element name="controller"  minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="control"  maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                            </xsd:sequence>
+                            <xsd:attribute name="signalId" type="xsd:string"/>
+                            <xsd:attribute name="type"     type="xsd:string"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="id"       type="xsd:string"/>
+                <xsd:attribute name="name"     type="xsd:string"/>
+                <xsd:attribute name="sequence" type="xsd:int"/>
+            </xsd:complexType>
+        </xsd:element> <!-- end controller -->
+
+        <xsd:element name="junction"  minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="connection"  maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="laneLink"  minOccurs="0" maxOccurs="unbounded">
+                                    <xsd:complexType>
+                                        <xsd:sequence>
+                                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                        </xsd:sequence>
+                                        <xsd:attribute name="from" type="xsd:int"/>
+                                        <xsd:attribute name="to"   type="xsd:int"/>
+                                    </xsd:complexType>
+                                </xsd:element>
+                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                            </xsd:sequence>
+                            <xsd:attribute name="id"             type="xsd:string"/>
+                            <xsd:attribute name="incomingRoad"   type="xsd:string"/>
+                            <xsd:attribute name="connectingRoad" type="xsd:string"/>
+                            <xsd:attribute name="contactPoint"   type="contactPoint"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="priority"  minOccurs="0" maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                            </xsd:sequence>
+                            <xsd:attribute name="high" type="xsd:string"/>
+                            <xsd:attribute name="low"  type="xsd:string"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="controller"  minOccurs="0" maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                            </xsd:sequence>
+                            <xsd:attribute name="id"       type="xsd:string"/>
+                            <xsd:attribute name="type"     type="xsd:string"/>
+                            <xsd:attribute name="sequence" type="xsd:int"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="name" type="xsd:string"/>
+                <xsd:attribute name="id"   type="xsd:string"/>
+            </xsd:complexType>
+        </xsd:element> <!-- end junction -->
+        
+        <xsd:element name="junctionGroup"  minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="junctionReference" maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:attribute name="junction" type="xsd:string"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="name" type="xsd:string"/>
+                <xsd:attribute name="id"   type="xsd:string"/>
+                <xsd:attribute name="type" type="junctionGroupType"/>
+            </xsd:complexType>
+        </xsd:element> <!-- end junctionGroup -->
+        
+        <xsd:element name="station"  minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="platform" minOccurs="1" maxOccurs="unbounded">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="segment"  minOccurs="1" maxOccurs="unbounded">
+                                    <xsd:complexType>
+                                        <xsd:sequence>
+                                            <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                                            <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                                        </xsd:sequence>
+                                        <xsd:attribute name="roadId" type="xsd:string"/>
+                                        <xsd:attribute name="sStart" type="xsd:double"/>
+                                        <xsd:attribute name="sEnd"   type="xsd:double"/>
+                                        <xsd:attribute name="side"   type="side"/>
+                                    </xsd:complexType>
+                                </xsd:element>
+                            </xsd:sequence>
+                            <xsd:attribute name="name" type="xsd:string"/>
+                            <xsd:attribute name="id"   type="xsd:string"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="name" type="xsd:string"/>
+                <xsd:attribute name="id"   type="xsd:string"/>
+                <xsd:attribute name="type" type="stationType"/>
+            </xsd:complexType>
+        </xsd:element> <!-- end station -->
+        
+        </xsd:sequence>
+    </xsd:complexType>
+</xsd:element>
+
+<!-- enumerations for road->link->Predecessor/successor->elementType -->
+<xsd:simpleType name="elementType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="road"/>
+       <xsd:enumeration value="junction"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for road->type->speed->max -->
+<xsd:simpleType name="max">
+<xsd:union>
+<xsd:simpleType>
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="no limit"/>
+       <xsd:enumeration value="undefined"/>
+   </xsd:restriction>
+ </xsd:simpleType>
+ <xsd:simpleType>
+   <xsd:restriction base="xsd:integer">
+       <xsd:minInclusive value="0"/>
+   </xsd:restriction>
+ </xsd:simpleType>  
+    </xsd:union>
+</xsd:simpleType>
+
+<!-- enumerations for road->link->Predecessor/successor->contactPoint -->
+<!-- enumerations for junction->connection->contactPoint -->
+<xsd:simpleType name="contactPoint">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="start"/>
+       <xsd:enumeration value="end"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for road->link->neighbor->side -->
+<!-- enumerations for openDRIVE->station->platform->segment->side -->
+<xsd:simpleType name="side">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="left"/>
+       <xsd:enumeration value="right"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for road->link->neighbor->direction-->
+<xsd:simpleType name="direction">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="same"/>
+       <xsd:enumeration value="opposite"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for road->type-->
+<xsd:simpleType name="roadType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="unknown"/>
+       <xsd:enumeration value="rural"/>
+       <xsd:enumeration value="motorway"/>
+       <xsd:enumeration value="town"/>
+       <xsd:enumeration value="lowSpeed"/>
+       <xsd:enumeration value="pedestrian"/>
+       <xsd:enumeration value="bicycle"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for road->type->speed->unit-->
+<!-- enumerations for lane->speed->unit-->
+<!-- enumerations for signals->signal->unit-->
+<xsd:simpleType name="unit">
+   <xsd:restriction base="xsd:string">
+      <xsd:enumeration value="m"/>
+       <xsd:enumeration value="km"/>
+       <xsd:enumeration value="ft"/>
+        <xsd:enumeration value="mile"/>
+       <xsd:enumeration value="m/s"/>
+       <xsd:enumeration value="mph"/>
+       <xsd:enumeration value="km/h"/>
+       <xsd:enumeration value="kg"/>
+       <xsd:enumeration value="t"/>
+       <xsd:enumeration value="%"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+
+<!-- enumerations for planView->geometry->paramPoly3->pRange-->
+<xsd:simpleType name="pRange">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="arcLength"/>
+       <xsd:enumeration value="normalized"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lateralProfile->crossFall->side -->
+<xsd:simpleType name="crossfallSide">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="left"/>
+       <xsd:enumeration value="right"/>
+       <xsd:enumeration value="both"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lanes->laneSection->singleSide -->
+<!-- enumerations for lane->level -->
+<!-- enumerations for centerLane->level -->
+<xsd:simpleType name="singleSide">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="true"/>
+       <xsd:enumeration value="false"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->type -->
+<!-- enumerations for centerLane->type -->
+<xsd:simpleType name="laneType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="none"/>
+       <xsd:enumeration value="driving"/>
+       <xsd:enumeration value="stop"/>
+       <xsd:enumeration value="shoulder"/>
+       <xsd:enumeration value="biking"/>
+       <xsd:enumeration value="sidewalk"/>
+       <xsd:enumeration value="border"/>
+       <xsd:enumeration value="restricted"/>
+       <xsd:enumeration value="parking"/>
+       <xsd:enumeration value="bidirectional"/>
+       <xsd:enumeration value="median"/>
+       <xsd:enumeration value="special1"/>
+       <xsd:enumeration value="special2"/>
+       <xsd:enumeration value="special3"/>
+       <xsd:enumeration value="roadWorks"/>
+       <xsd:enumeration value="tram"/>
+       <xsd:enumeration value="rail"/>
+       <xsd:enumeration value="entry"/>
+       <xsd:enumeration value="exit"/>
+       <xsd:enumeration value="offRamp"/>
+       <xsd:enumeration value="onRamp"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->roadMark->type -->
+<!-- enumerations for parkingSpace->marking->type -->
+<!-- enumerations for centerLane->roadMark->type -->
+<xsd:simpleType name="roadmarkType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="none"/>
+       <xsd:enumeration value="solid"/>
+       <xsd:enumeration value="broken"/>
+       <xsd:enumeration value="solid solid"/>
+        <xsd:enumeration value="solid broken"/>
+       <xsd:enumeration value="broken solid"/>
+       <xsd:enumeration value="broken broken"/>
+       <xsd:enumeration value="botts dots"/>
+       <xsd:enumeration value="grass"/>
+       <xsd:enumeration value="curb"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->roadMark->weight -->
+<!-- enumerations for centerLane->roadMark->weight -->
+<xsd:simpleType name="weight">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="standard"/>
+       <xsd:enumeration value="bold"/>       
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->roadMark->color -->
+<!-- enumerations for parkingSpace->marking->color -->
+<!-- enumerations for centerLane->roadMark->weight -->
+<xsd:simpleType name="color">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="standard"/>
+       <xsd:enumeration value="blue"/> 
+       <xsd:enumeration value="green"/>
+       <xsd:enumeration value="red"/> 
+       <xsd:enumeration value="white"/>
+       <xsd:enumeration value="yellow"/>       
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->access->restriction -->
+<xsd:simpleType name="restriction">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="simulator"/>
+       <xsd:enumeration value="autonomous traffic"/> 
+       <xsd:enumeration value="pedestrian"/>
+       <xsd:enumeration value="none"/>             
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->roadMark->laneChange -->
+<!-- enumerations for centerLane->roadMark->weight -->
+<xsd:simpleType name="laneChange">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="increase"/>
+       <xsd:enumeration value="decrease"/>
+       <xsd:enumeration value="both"/>
+       <xsd:enumeration value="none"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for lane->roadMark->type->line->rule -->
+<!-- enumerations for centerLane->roadMark->type->line->rule -->
+<xsd:simpleType name="rule">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="no passing"/>
+       <xsd:enumeration value="caution"/>
+       <xsd:enumeration value="none"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for objects->object->orientation -->
+<!-- enumerations for objects->objectReference->orientation -->
+<!-- enumerations for signals->signal->orientation -->
+<!-- enumerations for signals->signalReference->orientation -->
+<xsd:simpleType name="orientation">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="+"/>
+       <xsd:enumeration value="-"/>
+       <xsd:enumeration value="none"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for objects->tunnel->type -->
+<xsd:simpleType name="tunnelType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="standard"/>
+       <xsd:enumeration value="underpass"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for objects->bridge->type -->
+<xsd:simpleType name="bridgeType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="concrete"/>
+       <xsd:enumeration value="steel"/>
+       <xsd:enumeration value="brick"/>
+       <xsd:enumeration value="wood"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for parkingSpace->access -->
+<xsd:simpleType name="access">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="all"/>
+       <xsd:enumeration value="car"/>
+       <xsd:enumeration value="women"/>
+        <xsd:enumeration value="handicapped"/>
+       <xsd:enumeration value="bus"/>
+       <xsd:enumeration value="truck"/>
+       <xsd:enumeration value="electric"/>
+       <xsd:enumeration value="residents"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for parkingSpace->marking->side -->
+<xsd:simpleType name="parkingSpacemarkingSide">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="front"/>
+       <xsd:enumeration value="rear"/>
+       <xsd:enumeration value="left"/>
+        <xsd:enumeration value="right"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for signals->signal->dynamic -->
+<xsd:simpleType name="dynamic">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="yes"/>
+       <xsd:enumeration value="no"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for surface->CRG->orientation -->
+<xsd:simpleType name="surfaceOrientation">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="same"/>
+       <xsd:enumeration value="opposite"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for surface->CRG->mode -->
+<xsd:simpleType name="mode">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="attached"/>
+       <xsd:enumeration value="attached0"/>
+       <xsd:enumeration value="genuine"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for surface->CRG->purpose -->
+<xsd:simpleType name="purpose">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="elevation"/>
+       <xsd:enumeration value="friction"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for railRoad->switch->position -->
+<xsd:simpleType name="position">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="dynamic"/>
+       <xsd:enumeration value="straight"/>
+       <xsd:enumeration value="turn"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for railRoad->switch->mainTrack->dir-->
+<!-- enumerations for railRoad->switch->sideTrack->dir-->
+<xsd:simpleType name="dir">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="+"/>
+       <xsd:enumeration value="-"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for openDRIVE->junctionGroup->type-->
+<xsd:simpleType name="junctionGroupType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="roundabout"/>
+       <xsd:enumeration value="unknown"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<!-- enumerations for openDRIVE->station->type-->
+<xsd:simpleType name="stationType">
+   <xsd:restriction base="xsd:string">
+       <xsd:enumeration value="small"/>
+       <xsd:enumeration value="medium"/>
+       <xsd:enumeration value="large"/>
+   </xsd:restriction>
+</xsd:simpleType>
+
+<xsd:complexType name="userData" mixed="true">
+    <xsd:sequence>
+        <xsd:any minOccurs="0" maxOccurs="unbounded" processContents="skip"/>
+    </xsd:sequence>
+    <xsd:attribute name="code"  type="xsd:string"/>
+    <xsd:attribute name="value" type="xsd:string"/>
+</xsd:complexType>
+
+<xsd:complexType name="include" >
+    <xsd:attribute name="file" type="xsd:string"/>
+</xsd:complexType>
+
+<xsd:complexType name="laneValidity">
+    <xsd:sequence>
+        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+    </xsd:sequence>
+    <xsd:attribute name="fromLane" type="xsd:int"/>
+    <xsd:attribute name="toLane"   type="xsd:int"/>
+</xsd:complexType>
+
+<xsd:complexType name="parkingSpace">
+    <xsd:sequence>
+        <xsd:element name="marking" minOccurs="0" maxOccurs="4">
+            <xsd:complexType>
+                <xsd:attribute name="side"  type="parkingSpacemarkingSide"/>
+                <xsd:attribute name="type"  type="roadmarkType"/>
+                <xsd:attribute name="width" type="xsd:double"/>
+                <xsd:attribute name="color" type="color"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+    </xsd:sequence>
+    <xsd:attribute name="access"      type="access"/>
+    <xsd:attribute name="restrictions" type="xsd:string"/>
+</xsd:complexType>
+
+<xsd:complexType name="lane" >
+    <xsd:sequence>
+        <xsd:element name="link" minOccurs="0" maxOccurs="1">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="predecessor" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:attribute name="id" type="xsd:int"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="successor" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:attribute name="id" type="xsd:int"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+            </xsd:complexType>
+         </xsd:element>
+	 <xsd:choice>
+         <xsd:element name="width" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="a"       type="xsd:double"/>
+                <xsd:attribute name="b"       type="xsd:double"/>
+                <xsd:attribute name="c"       type="xsd:double"/>
+                <xsd:attribute name="d"       type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="border" minOccurs="1" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="a"       type="xsd:double"/>
+                <xsd:attribute name="b"       type="xsd:double"/>
+                <xsd:attribute name="c"       type="xsd:double"/>
+                <xsd:attribute name="d"       type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+      </xsd:choice>
+      <xsd:element name="roadMark" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="type" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="line" minOccurs="1" maxOccurs="unbounded">
+                                    <xsd:complexType>
+                                        <xsd:attribute name="length"  type="xsd:double"/>
+                                        <xsd:attribute name="space"   type="xsd:double"/>
+                                        <xsd:attribute name="tOffset" type="xsd:double"/>
+                                        <xsd:attribute name="sOffset" type="xsd:double"/>
+                                        <xsd:attribute name="rule"    type="rule"/>
+                                        <xsd:attribute name="width"   type="xsd:double"/>
+                                    </xsd:complexType>
+                                </xsd:element>
+                            </xsd:sequence>
+                            <xsd:attribute name="name"  type="xsd:string"/>
+                            <xsd:attribute name="width" type="xsd:double"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset"    type="xsd:double"/>
+                <xsd:attribute name="type"       type="roadmarkType"/>
+                <xsd:attribute name="weight"     type="weight"/>
+                <xsd:attribute name="color"      type="color"/>
+                <xsd:attribute name="material"   type="xsd:string"/>
+                <xsd:attribute name="width"      type="xsd:double"/>
+                <xsd:attribute name="laneChange" type="laneChange"/>
+	        <xsd:attribute name="height"     type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="material" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset"   type="xsd:double"/>
+                <xsd:attribute name="surface"   type="xsd:string"/>
+                <xsd:attribute name="friction"  type="xsd:double"/>
+                <xsd:attribute name="roughness" type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="visibility" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="forward" type="xsd:double"/>
+                <xsd:attribute name="back"    type="xsd:double"/>
+                <xsd:attribute name="left"    type="xsd:double"/>
+                <xsd:attribute name="right"   type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="speed" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="max"     type="xsd:double"/>
+                <xsd:attribute name="unit"    type="unit"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="access" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include" type="include" minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset"     type="xsd:double"/>
+                <xsd:attribute name="restriction" type="restriction"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="height" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include" type="include" minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="inner"   type="xsd:double"/>
+                <xsd:attribute name="outer"   type="xsd:double"/>
+            </xsd:complexType>
+        </xsd:element>
+	<xsd:element name="rule" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include" type="include" minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset" type="xsd:double"/>
+                <xsd:attribute name="value"   type="xsd:string"/>
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+    </xsd:sequence>
+    <xsd:attribute name="id"    type="xsd:int"/>
+    <xsd:attribute name="type"  type="laneType"/>
+    <xsd:attribute name="level" type="singleSide"/>
+</xsd:complexType>
+
+<xsd:complexType name="centerLane" >
+    <xsd:sequence>
+        <xsd:element name="link" minOccurs="0" maxOccurs="1">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="predecessor" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:attribute name="id" type="xsd:int"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="successor" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:attribute name="id" type="xsd:int"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+            </xsd:complexType>
+         </xsd:element>
+        <xsd:element name="roadMark" minOccurs="0" maxOccurs="unbounded">
+            <xsd:complexType>
+                <xsd:sequence>
+                    <xsd:element name="type" minOccurs="0" maxOccurs="1">
+                        <xsd:complexType>
+                            <xsd:sequence>
+                                <xsd:element name="line" minOccurs="1" maxOccurs="unbounded">
+                                    <xsd:complexType>
+                                        <xsd:attribute name="length"  type="xsd:double"/>
+                                        <xsd:attribute name="space"   type="xsd:double"/>
+                                        <xsd:attribute name="tOffset" type="xsd:double"/>
+                                        <xsd:attribute name="sOffset" type="xsd:double"/>
+                                        <xsd:attribute name="rule"    type="rule"/>
+					<xsd:attribute name="width"   type="xsd:double"/>
+                                    </xsd:complexType>
+                                </xsd:element>
+                            </xsd:sequence>
+                            <xsd:attribute name="name"  type="xsd:string"/>
+                            <xsd:attribute name="width" type="xsd:double"/>
+                        </xsd:complexType>
+                    </xsd:element>
+                    <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+                    <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+                </xsd:sequence>
+                <xsd:attribute name="sOffset"    type="xsd:double"/>
+                <xsd:attribute name="type"       type="roadmarkType"/>
+                <xsd:attribute name="weight"     type="weight"/>
+                <xsd:attribute name="color"      type="color"/>
+		<xsd:attribute name="material"   type="xsd:string"/>
+                <xsd:attribute name="width"      type="xsd:double"/>
+                <xsd:attribute name="laneChange" type="laneChange"/>
+		<xsd:attribute name="height"     type="xsd:double"/>
+		
+            </xsd:complexType>
+        </xsd:element>
+        <xsd:element name="userData" type="userData" minOccurs="0" maxOccurs="unbounded"/>
+        <xsd:element name="include"  type="include"  minOccurs="0" maxOccurs="unbounded"/>
+    </xsd:sequence>
+    <xsd:attribute name="id"    type="xsd:int"/>
+    <xsd:attribute name="type"  type="laneType"/>
+    <xsd:attribute name="level" type="singleSide"/>
+</xsd:complexType>
+
+
+</xsd:schema>
diff --git a/src/xml/adc_road.xodr b/src/xml/adc_road.xodr
new file mode 100644
index 0000000..6030acb
--- /dev/null
+++ b/src/xml/adc_road.xodr
@@ -0,0 +1,997 @@
+<?xml version="1.0" ?>
+<OpenDRIVE>
+    <header revMajor="1" revMinor="1" name="Testfile" version="1" date="Thu Feb 8 14:24:06 2007" north="0.0000000000000000e+00" south="0.0000000000000000e+00" east="0.0000000000000000e+00" west="0.0000000000000000e+00" />
+    <road name="road0" length="2.5000000000000000e+01" id="0" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="9" contactPoint="end" />
+            <successor elementType="junction" elementId="1" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="0.0000000000000000e+00" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="2.5000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road1" length="2.5000000000000000e+01" id="1" junction="-1">
+        <link>
+            <predecessor elementType="junction" elementId="1" contactPoint="end" />
+            <successor elementType="road" elementId="2" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="4.5000000000000000e+01" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="2.5000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road2" length="1.5707963270000000e+01" id="2" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="1" contactPoint="end" />
+            <successor elementType="road" elementId="3" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="7.0000000000000000e+01" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="7.0000999999999749e+01" y="1.6666666663690484e-08" hdg="5.0000000000000002e-05" length="1.5707963270000000e+01">
+                <arc curvature="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.5708963270000000e+01" x="8.0000499987499865e+01" y="1.0000500006217495e+01" hdg="1.5708463270000002e+00" length="-1.0000000000000000e-03">
+                <spiral curvStart="1.0000000000000001e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road3" length="6.0000000000000000e+01" id="3" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="2" contactPoint="end" />
+            <successor elementType="road" elementId="4" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="8.0000000000000000e+01" y="1.0000000000000000e+01" hdg="1.5707963270000000e+00" length="6.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road4" length="1.5707963270000000e+01" id="4" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="3" contactPoint="end" />
+            <successor elementType="road" elementId="5" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="8.0000000000000000e+01" y="7.0000000000000000e+01" hdg="1.5707963270000000e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="7.9999999983333140e+01" y="7.0000999999999749e+01" hdg="1.5708463270000002e+00" length="1.5707963270000000e+01">
+                <arc curvature="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.5708963270000000e+01" x="6.9999499991731369e+01" y="8.0000499985448712e+01" hdg="3.1416426540000000e+00" length="-1.0000000000000000e-03">
+                <spiral curvStart="1.0000000000000001e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road5" length="2.5000000000000000e+01" id="5" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="4" contactPoint="end" />
+            <successor elementType="junction" elementId="2" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="7.0000000000000000e+01" y="8.0000000000000000e+01" hdg="3.1415926540000001e+00" length="2.5000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road6" length="2.5000000000000000e+01" id="6" junction="-1">
+        <link>
+            <predecessor elementType="junction" elementId="2" contactPoint="end" />
+            <successor elementType="road" elementId="7" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="2.5000000000000000e+01" y="8.0000000000000000e+01" hdg="3.1415926540000001e+00" length="2.5000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road7" length="1.5707963270000000e+01" id="7" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="6" contactPoint="end" />
+            <successor elementType="road" elementId="8" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="0.0000000000000000e+00" y="8.0000000000000000e+01" hdg="3.1415926540000001e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="-9.9999999974999297e-04" y="7.9999999983332927e+01" hdg="3.1416426540000000e+00" length="1.5707963270000000e+01">
+                <arc curvature="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.5708963270000000e+01" x="-1.0000499983397582e+01" y="6.9999499989680245e+01" hdg="4.7124389810000000e+00" length="-1.0000000000000000e-03">
+                <spiral curvStart="1.0000000000000001e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road8" length="6.0000000000000000e+01" id="8" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="7" contactPoint="end" />
+            <successor elementType="road" elementId="9" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="-1.0000000000000000e+01" y="7.0000000000000000e+01" hdg="4.7123889800000001e+00" length="6.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road9" length="1.5707963270000000e+01" id="9" junction="-1">
+        <link>
+            <predecessor elementType="road" elementId="8" contactPoint="end" />
+            <successor elementType="road" elementId="0" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="-1.0000000000000000e+01" y="1.0000000000000000e+01" hdg="4.7123889800000001e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="-1.0000000272313564e+01" y="9.9990000000371886e+00" hdg="4.7123889800000001e+00" length="1.5707963270000000e+01">
+                <arc curvature="1.0000000000000001e-01" />
+            </geometry>
+            <geometry s="1.5707963270000000e+01" x="-3.3536281043515387e-03" y="-3.3892401329413957e-03" hdg="6.2831853070000001e+00" length="-1.0000000000000000e-03">
+                <spiral curvStart="1.0000000000000001e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="road10" length="6.0000000000000000e+01" id="10" junction="-1">
+        <link>
+            <predecessor elementType="junction" elementId="1" contactPoint="end" />
+            <successor elementType="junction" elementId="2" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="3.5000000000000000e+01" y="1.0000000000000000e+01" hdg="1.5707963270000000e+00" length="6.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <left>
+                    <lane id="1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </left>
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="0.0000000000000000e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="broken" weight="standard" color="standard" width="2.0000000000000001e-01" laneChange="both" />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <roadMark sOffset="0.0000000000000000e+00" type="solid" weight="standard" color="standard" width="2.9999999999999999e-01" laneChange="both" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_0_-1_1_-1" length="2.0000000000000000e+01" id="1000" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="0" contactPoint="end" />
+            <successor elementType="road" elementId="1" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="2.5000000000000000e+01" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="2.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_1_1_0_1" length="2.0000000000000000e+01" id="1001" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="1" contactPoint="start" />
+            <successor elementType="road" elementId="0" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="4.5000000000000000e+01" y="0.0000000000000000e+00" hdg="3.1415799999999998e+00" length="2.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_0_-1_10_-1" length="1.5709921586393582e+01" id="1002" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="0" contactPoint="end" />
+            <successor elementType="road" elementId="10" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="2.5000000000000000e+01" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="2.0510348974767112e-09">
+                <line />
+            </geometry>
+            <geometry s="2.0510348974767112e-09" x="2.5000000002051035e+01" y="0.0000000000000000e+00" hdg="0.0000000000000000e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000026537984180e-01" />
+            </geometry>
+            <geometry s="1.0000020510348975e-03" x="2.5001000002050784e+01" y="1.6666710893664086e-08" hdg="5.0000132689920889e-05" length="1.5707921584342548e+01">
+                <arc curvature="1.0000026537984180e-01" />
+            </geometry>
+            <geometry s="1.5708921586393583e+01" x="3.5000473451637099e+01" y="1.0000473468303746e+01" hdg="1.5708463271326900e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="1.0000026537984180e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_10_1_0_1" length="1.5709975894455384e+01" id="1003" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="10" contactPoint="start" />
+            <successor elementType="road" elementId="0" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="3.5000000000000000e+01" y="1.0000000000000000e+01" hdg="4.7123763269999994e+00" length="2.5306974480443500e-04">
+                <line />
+            </geometry>
+            <geometry s="2.5306974480443500e-04" x="3.4999999996797811e+01" y="9.9997469302552151e+00" hdg="4.7123763269999994e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="-1.0000153074568541e-01" />
+            </geometry>
+            <geometry s="1.2530697448044350e-03" x="3.4999999967477500e+01" y="9.9987469302557557e+00" hdg="4.7123263262346269e+00" length="1.5707722824710581e+01">
+                <arc curvature="-1.0000153074568541e-01" />
+            </geometry>
+            <geometry s="1.5708975894455385e+01" x="2.4999526525369703e+01" y="-4.7344598170084851e-04" hdg="3.1415299992346277e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="-1.0000153074568541e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_10_1_1_-1" length="1.5710120346678314e+01" id="1004" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="10" contactPoint="start" />
+            <successor elementType="road" elementId="1" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="3.5000000000000000e+01" y="1.0000000000000000e+01" hdg="4.7123763269999994e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="9.9998999976484537e-02" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="3.5000000004013110e+01" y="9.9990000000001178e+00" hdg="4.7124263264999877e+00" length="1.5707993813631946e+01">
+                <arc curvature="9.9998999976484537e-02" />
+            </geometry>
+            <geometry s="1.5708993813631945e+01" x="4.5000346926064282e+01" y="-7.2653541527145649e-04" hdg="6.2832099994999879e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="9.9998999976484537e-02" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+            <geometry s="1.5709993813631945e+01" x="4.5001346926062482e+01" y="-7.2647738995110136e-04" hdg="6.2832599989999762e+00" length="1.2653304636955909e-04">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_1_1_10_-1" length="1.5709921584511781e+01" id="1005" junction="1">
+        <link>
+            <predecessor elementType="road" elementId="1" contactPoint="start" />
+            <successor elementType="road" elementId="10" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="4.5000000000000000e+01" y="0.0000000000000000e+00" hdg="3.1415799999999998e+00" length="1.2653464747280907e-04">
+                <line />
+            </geometry>
+            <geometry s="1.2653464747280907e-04" x="4.4999873465352536e+01" y="1.6011175237333795e-09" hdg="3.1415799999999998e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="-1.0000026534682657e-01" />
+            </geometry>
+            <geometry s="1.1265346474728091e-03" x="4.4998873465353078e+01" y="3.0921418200480930e-08" hdg="3.1415299998673265e+00" length="1.5707795049864309e+01">
+                <arc curvature="-1.0000026534682657e-01" />
+            </geometry>
+            <geometry s="1.5708921584511781e+01" x="3.4999526548027013e+01" y="1.0000473474630535e+01" hdg="1.5707463268673272e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="-1.0000026534682657e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_5_-1_6_-1" length="2.0000000000000000e+01" id="1006" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="5" contactPoint="end" />
+            <successor elementType="road" elementId="6" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="4.5000000000000000e+01" y="7.9999999989744822e+01" hdg="3.1415926540000001e+00" length="2.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_5_-1_10_1" length="1.5709921580400758e+01" id="1007" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="5" contactPoint="end" />
+            <successor elementType="road" elementId="10" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="4.5000000000000000e+01" y="7.9999999989744822e+01" hdg="3.1415926540000001e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000026520325046e-01" />
+            </geometry>
+            <geometry s="1.0000000000000000e-03" x="4.4999000000000251e+01" y="7.9999999973077692e+01" hdg="3.1416426541326019e+00" length="1.5707795072416884e+01">
+                <arc curvature="1.0000026520325046e-01" />
+            </geometry>
+            <geometry s="1.5708795072416883e+01" x="3.4999526531330694e+01" y="6.9999653039344068e+01" hdg="4.7124263271326008e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="1.0000026520325046e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+            <geometry s="1.5709795072416883e+01" x="3.4999526602010867e+01" y="6.9998653039346678e+01" hdg="4.7124763272652022e+00" length="1.2650798387525697e-04">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_6_1_10_1" length="1.5709975881268994e+01" id="1008" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="6" contactPoint="start" />
+            <successor elementType="road" elementId="10" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="2.5000000000000000e+01" y="8.0000000000000000e+01" hdg="6.2831726539999995e+00" length="2.5305333638492300e-04">
+                <line />
+            </geometry>
+            <geometry s="2.5305333638492300e-04" x="2.5000253053336365e+01" y="7.9999999996798067e+01" hdg="6.2831726539999995e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="-1.0000153072517273e-01" />
+            </geometry>
+            <geometry s="1.2530533363849230e-03" x="2.5001253053335827e+01" y="7.9999999967477976e+01" hdg="6.2831226532346367e+00" length="1.5707722827932610e+01">
+                <arc curvature="-1.0000153072517273e-01" />
+            </geometry>
+            <geometry s="1.5708975881268994e+01" x="3.5000473433675587e+01" y="6.9999526525369802e+01" hdg="4.7123263262346367e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="-1.0000153072517273e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_6_1_5_1" length="2.0000000000000000e+01" id="1009" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="6" contactPoint="start" />
+            <successor elementType="road" elementId="5" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="2.5000000000000000e+01" y="8.0000000000000000e+01" hdg="6.2831726539999995e+00" length="2.0000000000000000e+01">
+                <line />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_10_-1_5_1" length="1.5710120342567388e+01" id="1010" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="10" contactPoint="end" />
+            <successor elementType="road" elementId="5" contactPoint="end" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="3.4999999987693798e+01" y="7.0000000000000000e+01" hdg="1.5707963270000000e+00" length="1.2650638310240936e-04">
+                <line />
+            </geometry>
+            <geometry s="1.2650638310240936e-04" x="3.4999999987693769e+01" y="7.0000126506383097e+01" hdg="1.5707963270000000e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="-9.9998999832913604e-02" />
+            </geometry>
+            <geometry s="1.1265063831024094e-03" x="3.5000000004360061e+01" y="7.0001126506382846e+01" hdg="1.5707463275000837e+00" length="1.5707993836184286e+01">
+                <arc curvature="-9.9998999832913604e-02" />
+            </geometry>
+            <geometry s="1.5709120342567388e+01" x="4.5000473468303561e+01" y="8.0000726519169589e+01" hdg="-3.7345499916519032e-05" length="1.0000000000000000e-03">
+                <spiral curvStart="-9.9998999832913604e-02" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <road name="junction_10_-1_6_-1" length="1.5709921580249619e+01" id="1011" junction="2">
+        <link>
+            <predecessor elementType="road" elementId="10" contactPoint="end" />
+            <successor elementType="road" elementId="6" contactPoint="start" />
+        </link>
+        <type s="0.0000000000000000e+00" type="town" />
+        <planView>
+            <geometry s="0.0000000000000000e+00" x="3.4999999987693798e+01" y="7.0000000000000000e+01" hdg="1.5707963270000000e+00" length="1.8459305195506204e-08">
+                <line />
+            </geometry>
+            <geometry s="1.8459305195506204e-08" x="3.4999999987693798e+01" y="7.0000000018459303e+01" hdg="1.5707963270000000e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="0.0000000000000000e+00" curvEnd="1.0000026552341455e-01" />
+            </geometry>
+            <geometry s="1.0000184593051955e-03" x="3.4999999971026881e+01" y="7.0001000018459052e+01" hdg="1.5708463271327617e+00" length="1.5707921561790315e+01">
+                <arc curvature="1.0000026552341455e-01" />
+            </geometry>
+            <geometry s="1.5708921580249619e+01" x="2.4999526531696123e+01" y="8.0000473451637035e+01" hdg="3.1416426541327618e+00" length="1.0000000000000000e-03">
+                <spiral curvStart="1.0000026552341455e-01" curvEnd="0.0000000000000000e+00" />
+            </geometry>
+        </planView>
+        <elevationProfile />
+        <lateralProfile />
+        <lanes>
+            <laneSection s="0.0000000000000000e+00">
+                <center>
+                    <lane id="0" type="driving" level="false">
+                        <link />
+                    </lane>
+                </center>
+                <right>
+                    <lane id="-1" type="driving" level="false">
+                        <link />
+                        <width sOffset="0.0000000000000000e+00" a="4.4000000000000004e+00" b="0.0000000000000000e+00" c="0.0000000000000000e+00" d="0.0000000000000000e+00" />
+                        <speed sOffset="0.0000000000000000e+00" max="6.0000000000000000e+01" />
+                    </lane>
+                </right>
+            </laneSection>
+        </lanes>
+        <objects />
+        <signals />
+    </road>
+    <junction name="junction_1" id="1">
+        <connection id="1" incomingRoad="0" connectingRoad="1" contactPoint="end">
+            <laneLink from="-1" to="-1" />
+        </connection>
+        <connection id="2" incomingRoad="1" connectingRoad="0" contactPoint="start">
+            <laneLink from="1" to="1" />
+        </connection>
+        <connection id="3" incomingRoad="0" connectingRoad="10" contactPoint="end">
+            <laneLink from="-1" to="-1" />
+        </connection>
+        <connection id="4" incomingRoad="10" connectingRoad="0" contactPoint="start">
+            <laneLink from="1" to="1" />
+        </connection>
+        <connection id="5" incomingRoad="10" connectingRoad="1" contactPoint="start">
+            <laneLink from="1" to="-1" />
+        </connection>
+        <connection id="6" incomingRoad="1" connectingRoad="10" contactPoint="start">
+            <laneLink from="1" to="-1" />
+        </connection>
+    </junction>
+    <junction name="junction_2" id="2">
+        <connection id="1" incomingRoad="5" connectingRoad="6" contactPoint="end">
+            <laneLink from="-1" to="-1" />
+        </connection>
+        <connection id="2" incomingRoad="5" connectingRoad="10" contactPoint="end">
+            <laneLink from="-1" to="1" />
+        </connection>
+        <connection id="3" incomingRoad="6" connectingRoad="10" contactPoint="start">
+            <laneLink from="1" to="1" />
+        </connection>
+        <connection id="4" incomingRoad="6" connectingRoad="5" contactPoint="start">
+            <laneLink from="1" to="1" />
+        </connection>
+        <connection id="5" incomingRoad="10" connectingRoad="5" contactPoint="end">
+            <laneLink from="-1" to="1" />
+        </connection>
+        <connection id="6" incomingRoad="10" connectingRoad="6" contactPoint="end">
+            <laneLink from="-1" to="-1" />
+        </connection>
+    </junction>
+</OpenDRIVE>
-- 
GitLab