From d37ad5b8ed27f4afb418d86a91ba5a8bda526348 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Sun, 10 Jan 2021 18:11:15 +0100
Subject: [PATCH] Changed the Point name to Pose.

---
 include/opendrive_arc.h          |   2 +-
 include/opendrive_common.h       |   6 +-
 include/opendrive_geometry.h     |  12 ++--
 include/opendrive_lane.h         |  16 ++---
 include/opendrive_line.h         |   2 +-
 include/opendrive_link.h         |   6 +-
 include/opendrive_object.h       |   8 +--
 include/opendrive_param_poly3.h  |   2 +-
 include/opendrive_road.h         |  14 ++--
 include/opendrive_road_node.h    |  18 ++---
 include/opendrive_road_segment.h |   8 +--
 include/opendrive_signal.h       |   6 +-
 include/opendrive_spiral.h       |   2 +-
 src/opendrive_arc.cpp            |   2 +-
 src/opendrive_geometry.cpp       |  30 ++++-----
 src/opendrive_lane.cpp           |  82 +++++++++++------------
 src/opendrive_line.cpp           |   2 +-
 src/opendrive_link.cpp           |  34 +++++-----
 src/opendrive_object.cpp         |  12 ++--
 src/opendrive_param_poly3.cpp    |   2 +-
 src/opendrive_road.cpp           |  68 +++++++++----------
 src/opendrive_road_node.cpp      | 110 +++++++++++++++----------------
 src/opendrive_road_segment.cpp   |  46 ++++++-------
 src/opendrive_signal.cpp         |  12 ++--
 src/opendrive_spiral.cpp         |   2 +-
 25 files changed, 252 insertions(+), 252 deletions(-)

diff --git a/include/opendrive_arc.h b/include/opendrive_arc.h
index 644278e..e5bc79f 100644
--- a/include/opendrive_arc.h
+++ b/include/opendrive_arc.h
@@ -11,7 +11,7 @@ class COpendriveArc : public COpendriveGeometry
   protected:
     COpendriveArc();
     COpendriveArc(const COpendriveArc &object);
-    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const;
+    virtual bool transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const;
     virtual void print(std::ostream &out);
     virtual void load_params(const planView::geometry_type &geometry_info);
     virtual std::string get_name(void);
diff --git a/include/opendrive_common.h b/include/opendrive_common.h
index 2cec3cf..6df1c57 100644
--- a/include/opendrive_common.h
+++ b/include/opendrive_common.h
@@ -24,21 +24,21 @@ typedef struct
   double s;
   double t;
   double heading;
-}TOpendriveTrackPoint;
+}TOpendriveTrackPose;
 
 typedef struct
 {
   double u;
   double v;
   double heading;
-}TOpendriveLocalPoint;
+}TOpendriveLocalPose;
 
 typedef struct
 {
   double x;
   double y;
   double heading;
-}TOpendriveWorldPoint;
+}TOpendriveWorldPose;
 
 typedef enum{OD_MARK_NONE,
              OD_MARK_SOLID,
diff --git a/include/opendrive_geometry.h b/include/opendrive_geometry.h
index f5a3caa..d54840d 100644
--- a/include/opendrive_geometry.h
+++ b/include/opendrive_geometry.h
@@ -19,25 +19,25 @@ class COpendriveGeometry
     double scale_factor;
     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) const = 0;
+    TOpendriveWorldPose pose;
+    virtual bool transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const = 0;
     virtual void print(std::ostream &out);
     virtual void load_params(const planView::geometry_type &geometry_info) = 0;
     virtual std::string get_name(void)=0;
     void set_scale_factor(double scale);
-    void set_start_point(TOpendriveWorldPoint &point);
+    void set_start_pose(TOpendriveWorldPose &pose);
     void set_max_s(double s);
     void set_min_s(double s);
   public:
     virtual COpendriveGeometry *clone(void) = 0;
-    bool get_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const;
-    bool get_world_pose(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world) const;
+    bool get_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const;
+    bool get_world_pose(TOpendriveTrackPose &track,TOpendriveWorldPose &world) const;
     bool in_range(double s) const;
     double get_length(void) const;
     virtual void get_curvature(double &start,double &end)=0;
     double get_max_s(void) const;
     double get_min_s(void) const;
-    TOpendriveWorldPoint get_start_point(void) const;
+    TOpendriveWorldPose get_start_pose(void) const;
     void operator=(const COpendriveGeometry &object);
     friend std::ostream& operator<<(std::ostream& out, COpendriveGeometry &geom);
     virtual ~COpendriveGeometry();
diff --git a/include/opendrive_lane.h b/include/opendrive_lane.h
index 4aa9964..6b91343 100644
--- a/include/opendrive_lane.h
+++ b/include/opendrive_lane.h
@@ -56,9 +56,9 @@ class COpendriveLane
     bool updated(lane_up_ref_t &refs);
     void update_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
     void clean_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
-    void update_start_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *start=NULL);
-    void update_end_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *end=NULL);
-    COpendriveLane *get_sub_lane(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *start=NULL,TOpendriveWorldPoint *end=NULL);
+    void update_start_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *start=NULL);
+    void update_end_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *end=NULL);
+    COpendriveLane *get_sub_lane(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *start=NULL,TOpendriveWorldPose *end=NULL);
     COpendriveLane *clone(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref);
   public:
     unsigned int get_num_nodes(void) const;
@@ -73,12 +73,12 @@ class COpendriveLane
     double get_offset(void) const;
     unsigned int get_index(void) const;
     int get_id(void) const;
-    TOpendriveWorldPoint get_start_point(void) const;
-    TOpendriveWorldPoint get_end_point(void) const;
+    TOpendriveWorldPose get_start_pose(void) const;
+    TOpendriveWorldPose get_end_pose(void) const;
     double get_length(void) const;
-    TOpendriveLocalPoint transform_to_local_point(TOpendriveTrackPoint &track);
-    TOpendriveWorldPoint transform_to_world_point(TOpendriveTrackPoint &track);
-    unsigned int get_closest_node_index(TOpendriveWorldPoint &point,double angle_tol=0.1);
+    TOpendriveLocalPose transform_to_local_pose(TOpendriveTrackPose &track);
+    TOpendriveWorldPose transform_to_world_pose(TOpendriveTrackPose &track);
+    unsigned int get_closest_node_index(TOpendriveWorldPose &pose,double angle_tol=0.1);
     friend std::ostream& operator<<(std::ostream& out, COpendriveLane &lane);
     ~COpendriveLane();
 };
diff --git a/include/opendrive_line.h b/include/opendrive_line.h
index 02a3cd2..3116aa9 100644
--- a/include/opendrive_line.h
+++ b/include/opendrive_line.h
@@ -10,7 +10,7 @@ class COpendriveLine : public COpendriveGeometry
   protected:
     COpendriveLine();
     COpendriveLine(const COpendriveGeometry &object);
-    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const;
+    virtual bool transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const;
     virtual void print(std::ostream &out);
     virtual void load_params(const planView::geometry_type &geometry_info);
     virtual std::string get_name(void);
diff --git a/include/opendrive_link.h b/include/opendrive_link.h
index 25c2916..ae6701b 100644
--- a/include/opendrive_link.h
+++ b/include/opendrive_link.h
@@ -36,8 +36,8 @@ class COpendriveLink
     void generate(double start_curvature,double end_curvature,double length,bool lane);
     void update_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lanei_refs,node_up_ref_t &node_refs);
     bool clean_references(node_up_ref_t &refs);
-    void update_start_pose(TOpendriveWorldPoint *start=NULL);
-    void update_end_pose(TOpendriveWorldPoint *end=NULL);
+    void update_start_pose(TOpendriveWorldPose *start=NULL);
+    void update_end_pose(TOpendriveWorldPose *end=NULL);
   public:
     const COpendriveRoadNode &get_prev(void) const;
     const COpendriveRoadNode &get_next(void) const;
@@ -46,7 +46,7 @@ class COpendriveLink
     const COpendriveLane &get_parent_lane(void) const;
     double get_resolution(void) const;
     double get_scale_factor(void) const;
-    double find_closest_world_point(TOpendriveWorldPoint &world,TOpendriveWorldPoint &point);
+    double find_closest_world_pose(TOpendriveWorldPose &world,TOpendriveWorldPose &pose);
     void get_trajectory(std::vector<double> &x, std::vector<double> &y,double start_length=0.0, double end_length=-1.0) const;
     void get_trajectory(std::vector<double> &x, std::vector<double> &y, std::vector<double> &yaw,double start_length=0.0, double end_length=-1.0) const;
     double get_length(void) const;
diff --git a/include/opendrive_object.h b/include/opendrive_object.h
index 8d2ea20..8804184 100644
--- a/include/opendrive_object.h
+++ b/include/opendrive_object.h
@@ -26,7 +26,7 @@ typedef struct
 
 typedef struct
 {  
-  TOpendriveTrackPoint vertices[OD_MAX_VERTICES];
+  TOpendriveTrackPose vertices[OD_MAX_VERTICES];
   double height[OD_MAX_VERTICES];
   unsigned int num_vertices;
 }TOpendrivePolygon;
@@ -46,7 +46,7 @@ class COpendriveObject
   private:
     COpendriveRoadSegment *segment;
     int id; ///< Object's id.
-    TOpendriveTrackPoint pose;
+    TOpendriveTrackPose pose;
     TOpendriveObject object;
     std::string type; ///< Object's OpenDrive type.
     std::string name; ///< Object's name.
@@ -60,8 +60,8 @@ class COpendriveObject
     COpendriveObject();
     COpendriveObject(const COpendriveObject& object);
     double get_scale_factor(void);
-    TOpendriveTrackPoint get_track_pose(void) const;
-    TOpendriveWorldPoint get_world_pose(void) const;
+    TOpendriveTrackPose get_track_pose(void) const;
+    TOpendriveWorldPose get_world_pose(void) const;
     int get_id(void) const;
     std::string get_type(void) const;
     std::string get_name(void) const;
diff --git a/include/opendrive_param_poly3.h b/include/opendrive_param_poly3.h
index cbb4943..2b03eb1 100644
--- a/include/opendrive_param_poly3.h
+++ b/include/opendrive_param_poly3.h
@@ -21,7 +21,7 @@ class COpendriveParamPoly3 : public COpendriveGeometry
   protected:
     COpendriveParamPoly3();
     COpendriveParamPoly3(const COpendriveParamPoly3 &object);
-    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const;
+    virtual bool transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const;
     virtual void print(std::ostream &out);
     virtual void load_params(const planView::geometry_type &geometry_info);
     virtual std::string get_name(void);
diff --git a/include/opendrive_road.h b/include/opendrive_road.h
index 4a75fa5..44cfea7 100644
--- a/include/opendrive_road.h
+++ b/include/opendrive_road.h
@@ -36,8 +36,8 @@ class COpendriveRoad
     void update_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
     void clean_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
     void prune(std::vector<unsigned int> &path_nodes);
-    bool node_exists_at(TOpendriveWorldPoint &pose);
-    COpendriveRoadNode* get_node_at(TOpendriveWorldPoint &pose);
+    bool node_exists_at(TOpendriveWorldPose &pose);
+    COpendriveRoadNode* get_node_at(TOpendriveWorldPose &pose);
   public:
     COpendriveRoad();
     COpendriveRoad(const COpendriveRoad& object);
@@ -53,11 +53,11 @@ class COpendriveRoad
     unsigned int get_num_nodes(void) const;
     const COpendriveRoadNode& get_node(unsigned int index) const;
     const COpendriveRoadSegment& operator[](std::size_t index);
-    unsigned int get_closest_node(TOpendriveWorldPoint &point,double angle_tol=0.1);
-    double get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol=0.1);
-    void get_closest_points(TOpendriveWorldPoint &point,std::vector<TOpendriveWorldPoint> &closest_points,std::vector<double> &closest_lengths,double dist_tol,double angle_tol=0.1);
-    std::vector<unsigned int> get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPoint &start_point,TOpendriveWorldPoint &end_point,COpendriveRoad &new_road);
-    void get_sub_road(TOpendriveWorldPoint &start_point,double length,COpendriveRoad &new_road);
+    unsigned int get_closest_node(TOpendriveWorldPose &pose,double angle_tol=0.1);
+    double get_closest_pose(TOpendriveWorldPose &pose,TOpendriveWorldPose &closest_pose,double angle_tol=0.1);
+    void get_closest_poses(TOpendriveWorldPose &pose,std::vector<TOpendriveWorldPose> &closest_poses,std::vector<double> &closest_lengths,double dist_tol,double angle_tol=0.1);
+    std::vector<unsigned int> get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPose &start_pose,TOpendriveWorldPose &end_pose,COpendriveRoad &new_road);
+    void get_sub_road(TOpendriveWorldPose &start_pose,double length,COpendriveRoad &new_road);
     void operator=(const COpendriveRoad& object);
     friend std::ostream& operator<<(std::ostream& out, COpendriveRoad &road);
     ~COpendriveRoad();
diff --git a/include/opendrive_road_node.h b/include/opendrive_road_node.h
index e0ca5f9..9951642 100644
--- a/include/opendrive_road_node.h
+++ b/include/opendrive_road_node.h
@@ -24,7 +24,7 @@ class COpendriveRoadNode
     std::vector<COpendriveLink *> links;
     double resolution;
     double scale_factor;
-    TOpendriveWorldPoint point;
+    TOpendriveWorldPose pose;
     std::vector<TOpendriveRoadNodeParent> parents;
     unsigned int index;
   protected:
@@ -41,7 +41,7 @@ class COpendriveRoadNode
     void set_resolution(double res);
     void set_scale_factor(double scale);
     void set_index(unsigned int index);
-    void set_point(TOpendriveWorldPoint &start);
+    void set_pose(TOpendriveWorldPose &start);
     void add_parent(const planView::geometry_type &geom_info,COpendriveLane *lane,COpendriveRoadSegment *segment);
     void add_parent(COpendriveGeometry *geometry,COpendriveLane *lane,COpendriveRoadSegment *segment);
     TOpendriveRoadNodeParent *get_parent_with_lane(const COpendriveLane *lane);
@@ -50,8 +50,8 @@ class COpendriveRoadNode
     COpendriveRoadNode *get_original_node(node_up_ref_t &node_refs);
     void update_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
     void clean_references(segment_up_ref_t &segment_refs,lane_up_ref_t &lane_refs,node_up_ref_t &node_refs);
-    void update_start_pose(COpendriveLane *lane,TOpendriveWorldPoint *start=NULL);
-    void update_end_pose(COpendriveLane *lane,TOpendriveWorldPoint *end=NULL);
+    void update_start_pose(COpendriveLane *lane,TOpendriveWorldPose *start=NULL);
+    void update_end_pose(COpendriveLane *lane,TOpendriveWorldPose *end=NULL);
   public:
     double get_resolution(void) const;
     double get_scale_factor(void) const;
@@ -60,14 +60,14 @@ class COpendriveRoadNode
     const COpendriveRoadSegment& get_parent_segment(unsigned int index) const;
     const COpendriveLane &get_parent_lane(unsigned int index) const;
     const COpendriveGeometry &get_geometry(unsigned int index) const;
-    TOpendriveWorldPoint get_point(void) const;
+    TOpendriveWorldPose get_pose(void) const;
     unsigned int get_num_links(void) const;
     const COpendriveLink &get_link(unsigned int index) const;
     const COpendriveLink &get_link_ending_at(unsigned int node_index) const;
-    unsigned int get_closest_link(TOpendriveWorldPoint &point,double angle_tol=0.1) const;
-    double get_closest_distance(TOpendriveWorldPoint &point,double angle_tol=0.1) const;
-    double get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol=0.1) const;
-    void get_closest_points(TOpendriveWorldPoint &point,std::vector<TOpendriveWorldPoint> &closest_points,std::vector<double> &closest_lengths,double dist_tol,double angle_tol=0.1) const;
+    unsigned int get_closest_link(TOpendriveWorldPose &pose,double angle_tol=0.1) const;
+    double get_closest_distance(TOpendriveWorldPose &pose,double angle_tol=0.1) const;
+    double get_closest_pose(TOpendriveWorldPose &pose,TOpendriveWorldPose &closest_pose,double angle_tol=0.1) const;
+    void get_closest_poses(TOpendriveWorldPose &pose,std::vector<TOpendriveWorldPose> &closest_poses,std::vector<double> &closest_lengths,double dist_tol,double angle_tol=0.1) const;
     friend std::ostream& operator<<(std::ostream& out, COpendriveRoadNode &node);
     ~COpendriveRoadNode();
 };
diff --git a/include/opendrive_road_segment.h b/include/opendrive_road_segment.h
index d06dbcc..d00bb7f 100644
--- a/include/opendrive_road_segment.h
+++ b/include/opendrive_road_segment.h
@@ -53,7 +53,7 @@ class COpendriveRoadSegment
     void remove_lane(COpendriveLane *lane);
     void add_nodes(OpenDRIVE::road_type &road_info);
     void add_node(const planView::geometry_type &geom_info,COpendriveLane *lane);
-    void add_empty_node(TOpendriveWorldPoint &point,COpendriveLane *lane);
+    void add_empty_node(TOpendriveWorldPose &pose,COpendriveLane *lane);
     void remove_node(COpendriveRoadNode *node);
     bool has_node(COpendriveRoadNode *node);
     int get_node_side(COpendriveRoadNode *node);
@@ -63,7 +63,7 @@ class COpendriveRoadSegment
     void link_segment(COpendriveRoadSegment *segment,int from,bool from_start, int to,bool to_start);
     bool connects_to(COpendriveRoadSegment *segment);
     bool connects_segments(COpendriveRoadSegment *segment1,COpendriveRoadSegment *segment2);
-    COpendriveRoadSegment *get_sub_segment(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,int node_side,TOpendriveWorldPoint *start=NULL,TOpendriveWorldPoint *end=NULL);
+    COpendriveRoadSegment *get_sub_segment(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,int node_side,TOpendriveWorldPose *start=NULL,TOpendriveWorldPose *end=NULL);
     COpendriveRoadSegment *clone(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref);
   public:
     std::string get_name(void) const;
@@ -80,8 +80,8 @@ class COpendriveRoadSegment
     const COpendriveObject &get_object(unsigned int index) const;
     unsigned int get_num_connecting(void) const;
     const COpendriveRoadSegment &get_connecting(unsigned int index) const;
-    TOpendriveLocalPoint transform_to_local_point(const TOpendriveTrackPoint &track);
-    TOpendriveWorldPoint transform_to_world_point(const TOpendriveTrackPoint &track);
+    TOpendriveLocalPose transform_to_local_pose(const TOpendriveTrackPose &track);
+    TOpendriveWorldPose transform_to_world_pose(const TOpendriveTrackPose &track);
     friend std::ostream& operator<<(std::ostream& out, COpendriveRoadSegment &segment);
     ~COpendriveRoadSegment();
 };
diff --git a/include/opendrive_signal.h b/include/opendrive_signal.h
index cce3f20..5dfe3df 100644
--- a/include/opendrive_signal.h
+++ b/include/opendrive_signal.h
@@ -15,7 +15,7 @@ class COpendriveSignal
   private:
     COpendriveRoadSegment *segment;
     int id; ///< Signal's id.
-    TOpendriveTrackPoint pose;
+    TOpendriveTrackPose pose;
     std::string type; ///< Signal's OpenDrive type.
     std::string sub_type; ///< Signal's OpenDrive subtype.
     int value; ///< Signal's value.
@@ -30,8 +30,8 @@ class COpendriveSignal
     COpendriveSignal(const COpendriveSignal &object);
     double get_scale_factor(void);
     int get_id(void) const;
-    TOpendriveTrackPoint get_track_pose(void) const;
-    TOpendriveWorldPoint get_world_pose(void) const;
+    TOpendriveTrackPose get_track_pose(void) const;
+    TOpendriveWorldPose get_world_pose(void) const;
     void get_type(std::string &type, std::string &sub_type) const;
     int get_value(void) const;
     std::string get_text(void) const;
diff --git a/include/opendrive_spiral.h b/include/opendrive_spiral.h
index 73624a0..12b0a36 100644
--- a/include/opendrive_spiral.h
+++ b/include/opendrive_spiral.h
@@ -12,7 +12,7 @@ class COpendriveSpiral : public COpendriveGeometry
   protected:
     COpendriveSpiral();
     COpendriveSpiral(const COpendriveSpiral &object);
-    virtual bool transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const;
+    virtual bool transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const;
     virtual void print(std::ostream &out);
     virtual void load_params(const planView::geometry_type &geometry_info);
     virtual std::string get_name(void);
diff --git a/src/opendrive_arc.cpp b/src/opendrive_arc.cpp
index 2610e34..b8567a0 100644
--- a/src/opendrive_arc.cpp
+++ b/src/opendrive_arc.cpp
@@ -11,7 +11,7 @@ COpendriveArc::COpendriveArc(const COpendriveArc &object) : COpendriveGeometry(o
   this->curvature=object.curvature;
 }
 
-bool COpendriveArc::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const
+bool COpendriveArc::transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const
 {
   double alpha;
 
diff --git a/src/opendrive_geometry.cpp b/src/opendrive_geometry.cpp
index a22bda5..82d9cd2 100644
--- a/src/opendrive_geometry.cpp
+++ b/src/opendrive_geometry.cpp
@@ -23,11 +23,11 @@ COpendriveGeometry::COpendriveGeometry(const COpendriveGeometry &object)
 
 void COpendriveGeometry::print(std::ostream& out)
 {
-  TOpendriveWorldPoint tmp_point=this->get_start_point();
+  TOpendriveWorldPose tmp_pose=this->get_start_pose();
 
   out << "        Geometry " << this->get_name() << std::endl; 
   out << "          lenght: " << this->get_length() << std::endl;
-  out << "          pose: x = " << tmp_point.x << ", y = " << tmp_point.y << ", heading = " << tmp_point.heading << std::endl;
+  out << "          pose: x = " << tmp_pose.x << ", y = " << tmp_pose.y << ", heading = " << tmp_pose.heading << std::endl;
 }
 
 void COpendriveGeometry::load(const planView::geometry_type &geometry_info)
@@ -45,11 +45,11 @@ void COpendriveGeometry::set_scale_factor(double scale)
   this->scale_factor=scale;
 }
 
-void COpendriveGeometry::set_start_point(TOpendriveWorldPoint &point)
+void COpendriveGeometry::set_start_pose(TOpendriveWorldPose &pose)
 {
-  this->pose.x=point.x*this->scale_factor;
-  this->pose.y=point.y*this->scale_factor;
-  this->pose.heading=point.heading;
+  this->pose.x=pose.x*this->scale_factor;
+  this->pose.y=pose.y*this->scale_factor;
+  this->pose.heading=pose.heading;
 }
 
 void COpendriveGeometry::set_max_s(double s)
@@ -62,14 +62,14 @@ void COpendriveGeometry::set_min_s(double s)
   this->min_s=s*this->scale_factor;
 }
 
-bool COpendriveGeometry::get_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const
+bool COpendriveGeometry::get_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const
 {
   return this->transform_local_pose(track,local);
 }
 
-bool COpendriveGeometry::get_world_pose(TOpendriveTrackPoint &track,TOpendriveWorldPoint &world) const
+bool COpendriveGeometry::get_world_pose(TOpendriveTrackPose &track,TOpendriveWorldPose &world) const
 {
-  TOpendriveLocalPoint local;
+  TOpendriveLocalPose local;
 
   if(this->transform_local_pose(track,local))
   {
@@ -105,15 +105,15 @@ double COpendriveGeometry::get_min_s(void) const
   return this->min_s/this->scale_factor;
 }
 
-TOpendriveWorldPoint COpendriveGeometry::get_start_point(void) const
+TOpendriveWorldPose COpendriveGeometry::get_start_pose(void) const
 {
-  TOpendriveWorldPoint tmp_point;
+  TOpendriveWorldPose tmp_pose;
   
-  tmp_point.x=this->pose.x/this->scale_factor;
-  tmp_point.y=this->pose.y/this->scale_factor;
-  tmp_point.heading=this->pose.heading;
+  tmp_pose.x=this->pose.x/this->scale_factor;
+  tmp_pose.y=this->pose.y/this->scale_factor;
+  tmp_pose.heading=this->pose.heading;
 
-  return tmp_point;
+  return tmp_pose;
 }
 
 void COpendriveGeometry::operator=(const COpendriveGeometry &object)
diff --git a/src/opendrive_lane.cpp b/src/opendrive_lane.cpp
index f93c25d..53dbe87 100644
--- a/src/opendrive_lane.cpp
+++ b/src/opendrive_lane.cpp
@@ -350,7 +350,7 @@ void COpendriveLane::clean_references(segment_up_ref_t &segment_refs,lane_up_ref
   }
 }
 
-void COpendriveLane::update_start_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *start)
+void COpendriveLane::update_start_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *start)
 {
   std::vector<COpendriveRoadNode *>::iterator it;
   segment_up_ref_t new_segment_ref;
@@ -393,7 +393,7 @@ void COpendriveLane::update_start_node(node_up_ref_t &new_node_ref,lane_up_ref_t
   this->nodes[0]->update_start_pose(this,start);
 }
 
-void COpendriveLane::update_end_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *end)
+void COpendriveLane::update_end_node(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *end)
 {
   std::vector<COpendriveRoadNode *>::iterator it;
   segment_up_ref_t new_segment_ref;
@@ -436,7 +436,7 @@ void COpendriveLane::update_end_node(node_up_ref_t &new_node_ref,lane_up_ref_t &
   this->nodes[this->nodes.size()-1]->update_end_pose(this,end);
 }
 
-COpendriveLane *COpendriveLane::get_sub_lane(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPoint *start,TOpendriveWorldPoint *end)
+COpendriveLane *COpendriveLane::get_sub_lane(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,TOpendriveWorldPose *start,TOpendriveWorldPose *end)
 {
   COpendriveLane *new_lane;
 
@@ -638,21 +638,21 @@ int COpendriveLane::get_id(void) const
   return this->id;
 }
 
-TOpendriveWorldPoint COpendriveLane::get_start_point(void) const
+TOpendriveWorldPose COpendriveLane::get_start_pose(void) const
 {
-  TOpendriveTrackPoint track_point;
-  TOpendriveWorldPoint world_point;
+  TOpendriveTrackPose track_pose;
+  TOpendriveWorldPose world_pose;
   TOpendriveRoadNodeParent *parent;
   std::stringstream error;
 
-  track_point.heading=0.0;
+  track_pose.heading=0.0;
   if(this->id<0)// right lane
   {
-    track_point.t=this->get_offset()-this->get_width()/2.0;
-    track_point.s=0.0;
+    track_pose.t=this->get_offset()-this->get_width()/2.0;
+    track_pose.s=0.0;
     parent=this->nodes[0]->get_parent_with_lane(this);
     if(parent!=NULL)
-      parent->geometry->get_world_pose(track_point,world_point);
+      parent->geometry->get_world_pose(track_pose,world_pose);
     else
     {
       error << "Node " << this->nodes[0]->get_index() << " does not have lane " << this->id << " of segment " << this->segment->get_name() << " as a parent";
@@ -661,12 +661,12 @@ TOpendriveWorldPoint COpendriveLane::get_start_point(void) const
   }
   else
   {
-    track_point.t=this->get_offset()+this->get_width()/2.0;
+    track_pose.t=this->get_offset()+this->get_width()/2.0;
     parent=this->nodes[0]->get_parent_with_lane(this);
     if(parent!=NULL)
     {
-      track_point.s=parent->geometry->get_length();
-      parent->geometry->get_world_pose(track_point,world_point);
+      track_pose.s=parent->geometry->get_length();
+      parent->geometry->get_world_pose(track_pose,world_pose);
     }
     else
     {
@@ -675,26 +675,26 @@ TOpendriveWorldPoint COpendriveLane::get_start_point(void) const
     }
   }
   if(this->id>0)
-    world_point.heading=normalize_angle(world_point.heading+3.14159);
+    world_pose.heading=normalize_angle(world_pose.heading+3.14159);
 
-  return world_point;
+  return world_pose;
 }
 
-TOpendriveWorldPoint COpendriveLane::get_end_point(void) const
+TOpendriveWorldPose COpendriveLane::get_end_pose(void) const
 {
-  TOpendriveTrackPoint track_point;
-  TOpendriveWorldPoint world_point;
+  TOpendriveTrackPose track_pose;
+  TOpendriveWorldPose world_pose;
   TOpendriveRoadNodeParent *parent;
   std::stringstream error;
   
-  track_point.heading=0.0;
+  track_pose.heading=0.0;
   if(this->id>0)// left lane
   { 
-    track_point.t=this->get_offset()+this->get_width()/2.0;
-    track_point.s=0.0;
+    track_pose.t=this->get_offset()+this->get_width()/2.0;
+    track_pose.s=0.0;
     parent=this->nodes[this->nodes.size()-1]->get_parent_with_lane(this);
     if(parent!=NULL)
-      parent->geometry->get_world_pose(track_point,world_point);
+      parent->geometry->get_world_pose(track_pose,world_pose);
     else
     {
       error << "Node " << this->nodes[this->nodes.size()-1]->get_index() << " does not have lane " << this->id << " of segment " << this->segment->get_name() << " as a parent";
@@ -703,12 +703,12 @@ TOpendriveWorldPoint COpendriveLane::get_end_point(void) const
   }
   else
   { 
-    track_point.t=this->get_offset()-this->get_width()/2.0;
+    track_pose.t=this->get_offset()-this->get_width()/2.0;
     parent=this->nodes[this->nodes.size()-1]->get_parent_with_lane(this);
     if(parent!=NULL)
     {
-      track_point.s=parent->geometry->get_length();
-      parent->geometry->get_world_pose(track_point,world_point);
+      track_pose.s=parent->geometry->get_length();
+      parent->geometry->get_world_pose(track_pose,world_pose);
     }
     else
     {
@@ -717,9 +717,9 @@ TOpendriveWorldPoint COpendriveLane::get_end_point(void) const
     }
   }
   if(this->id>0)
-    world_point.heading=normalize_angle(world_point.heading+3.14159);
+    world_pose.heading=normalize_angle(world_pose.heading+3.14159);
 
-  return world_point;
+  return world_pose;
 }
 
 double COpendriveLane::get_length(void) const
@@ -743,15 +743,15 @@ double COpendriveLane::get_length(void) const
   return length;
 }
 
-TOpendriveLocalPoint COpendriveLane::transform_to_local_point(TOpendriveTrackPoint &track)
+TOpendriveLocalPose COpendriveLane::transform_to_local_pose(TOpendriveTrackPose &track)
 {
-  TOpendriveLocalPoint local;
+  TOpendriveLocalPose local;
   TOpendriveRoadNodeParent *parent;
   std::stringstream error;
 
   if(track.s<0.0)
   {
-    error << "Invalid track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
+    error << "Invalid track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
     throw CException(_HERE_,error.str());
   }
   for(unsigned int i=0;i<this->nodes.size();i++)
@@ -763,7 +763,7 @@ TOpendriveLocalPoint COpendriveLane::transform_to_local_point(TOpendriveTrackPoi
       { 
         if(!parent->geometry->get_local_pose(track,local))
         {
-          error << "Impossible to transform to local coordinates point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") in lane " << parent->lane->get_id() << " of segment " << parent->segment->get_name();
+          error << "Impossible to transform to local coordinates pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") in lane " << parent->lane->get_id() << " of segment " << parent->segment->get_name();
           throw CException(_HERE_,error.str());
         }
         return local;
@@ -778,19 +778,19 @@ TOpendriveLocalPoint COpendriveLane::transform_to_local_point(TOpendriveTrackPoi
     }
   }
 
-  error << "Track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") does not belong to lane  " << this->id << " of segment " << this->segment->get_name();
+  error << "Track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") does not belong to lane  " << this->id << " of segment " << this->segment->get_name();
   throw CException(_HERE_,error.str());
 }
 
-TOpendriveWorldPoint COpendriveLane::transform_to_world_point(TOpendriveTrackPoint &track)
+TOpendriveWorldPose COpendriveLane::transform_to_world_pose(TOpendriveTrackPose &track)
 { 
-  TOpendriveWorldPoint world;
+  TOpendriveWorldPose world;
   TOpendriveRoadNodeParent *parent;
   std::stringstream error;
 
   if(track.s<0.0)
   {
-    error << "Invalid track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
+    error << "Invalid track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
     throw CException(_HERE_,error.str());
   }
   for(unsigned int i=0;i<this->nodes.size();i++)
@@ -802,7 +802,7 @@ TOpendriveWorldPoint COpendriveLane::transform_to_world_point(TOpendriveTrackPoi
       {
         if(!parent->geometry->get_world_pose(track,world))
         {
-          error << "Impossible to transform to local coordinates point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") in lane " << parent->lane->get_id() << " of segment " << parent->segment->get_name();
+          error << "Impossible to transform to local coordinates pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") in lane " << parent->lane->get_id() << " of segment " << parent->segment->get_name();
           throw CException(_HERE_,error.str());
         }
         return world;
@@ -817,20 +817,20 @@ TOpendriveWorldPoint COpendriveLane::transform_to_world_point(TOpendriveTrackPoi
     }
   }
 
-  error << "Track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") does not belong to lane  " << this->id << " of segment " << this->segment->get_name();
+  error << "Track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ") does not belong to lane  " << this->id << " of segment " << this->segment->get_name();
   throw CException(_HERE_,error.str());
 }
 
-unsigned int COpendriveLane::get_closest_node_index(TOpendriveWorldPoint &point,double angle_tol)
+unsigned int COpendriveLane::get_closest_node_index(TOpendriveWorldPose &pose,double angle_tol)
 {
   double dist,min_dist=std::numeric_limits<double>::max();
-  TOpendriveWorldPoint found_point;
+  TOpendriveWorldPose found_pose;
   unsigned int closest_index=-1;
 
   for(unsigned int i=0;i<this->nodes.size();i++)
   {
-    this->nodes[i]->get_closest_point(point,found_point,angle_tol);
-    dist=sqrt(pow(found_point.x-point.x,2.0)+pow(found_point.y-point.y,2.0));
+    this->nodes[i]->get_closest_pose(pose,found_pose,angle_tol);
+    dist=sqrt(pow(found_pose.x-pose.x,2.0)+pow(found_pose.y-pose.y,2.0));
     if(dist<min_dist)
     {
       min_dist=dist;
diff --git a/src/opendrive_line.cpp b/src/opendrive_line.cpp
index e25c7b6..3f82f4d 100644
--- a/src/opendrive_line.cpp
+++ b/src/opendrive_line.cpp
@@ -10,7 +10,7 @@ COpendriveLine::COpendriveLine(const COpendriveGeometry &object) : COpendriveGeo
 
 }
 
-bool COpendriveLine::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const
+bool COpendriveLine::transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const
 {
   local.u=track.s;
   local.v=track.t;
diff --git a/src/opendrive_link.cpp b/src/opendrive_link.cpp
index 4e8ca60..5aff42f 100644
--- a/src/opendrive_link.cpp
+++ b/src/opendrive_link.cpp
@@ -62,15 +62,15 @@ void COpendriveLink::set_scale_factor(double scale)
 
 void COpendriveLink::generate(double start_curvature,double end_curvature,double length,bool lane)
 {
-  TOpendriveWorldPoint node_start,node_end;
+  TOpendriveWorldPose node_start,node_end;
   TPoint start,end;
 
-  node_start=this->prev->get_point();
+  node_start=this->prev->get_pose();
   start.x=node_start.x;
   start.y=node_start.y;
   start.heading=node_start.heading;
   start.curvature=start_curvature;
-  node_end=this->next->get_point();
+  node_end=this->next->get_pose();
   end.x=node_end.x;
   end.y=node_end.y;
   end.heading=node_end.heading;
@@ -105,33 +105,33 @@ bool COpendriveLink::clean_references(node_up_ref_t &refs)
   return false;
 }
 
-void COpendriveLink::update_start_pose(TOpendriveWorldPoint *start)
+void COpendriveLink::update_start_pose(TOpendriveWorldPose *start)
 {
-  TPoint start_point;
+  TPoint start_pose;
   double length;
 
   if(start==NULL)
     return;
   if(this->spline!=NULL)
   {
-    length=this->spline->find_closest_point(start->x,start->y,start_point);
+    length=this->spline->find_closest_point(start->x,start->y,start_pose);
     length=this->spline->get_length()-length;
-    this->spline->set_start_point(start_point);
+    this->spline->set_start_point(start_pose);
     this->spline->generate(this->resolution,length);
   }
 }
 
-void COpendriveLink::update_end_pose(TOpendriveWorldPoint *end)
+void COpendriveLink::update_end_pose(TOpendriveWorldPose *end)
 {
-  TPoint end_point;
+  TPoint end_pose;
   double length;
 
   if(end==NULL)
     return;
   if(this->spline!=NULL)
   {
-    length=this->spline->find_closest_point(end->x,end->y,end_point);
-    this->spline->set_end_point(end_point);
+    length=this->spline->find_closest_point(end->x,end->y,end_pose);
+    this->spline->set_end_point(end_pose);
     this->spline->generate(this->resolution,length);
   }
 }
@@ -171,17 +171,17 @@ double COpendriveLink::get_scale_factor(void) const
   return this->scale_factor;
 }
 
-double COpendriveLink::find_closest_world_point(TOpendriveWorldPoint &world,TOpendriveWorldPoint &point)
+double COpendriveLink::find_closest_world_pose(TOpendriveWorldPose &world,TOpendriveWorldPose &pose)
 {
-  TPoint spline_point;
+  TPoint spline_pose;
   double length;
 
   if(this->spline!=NULL)
   {
-    length=this->spline->find_closest_point(world.x,world.y,spline_point);
-    point.x=spline_point.x;
-    point.y=spline_point.y;
-    point.heading=normalize_angle(spline_point.heading);
+    length=this->spline->find_closest_point(world.x,world.y,spline_pose);
+    pose.x=spline_pose.x;
+    pose.y=spline_pose.y;
+    pose.heading=normalize_angle(spline_pose.heading);
   }
   else
     length=std::numeric_limits<double>::max();
diff --git a/src/opendrive_object.cpp b/src/opendrive_object.cpp
index 786ee2a..48cb8c5 100644
--- a/src/opendrive_object.cpp
+++ b/src/opendrive_object.cpp
@@ -90,7 +90,7 @@ void COpendriveObject::load(objects::object_type &object_info,COpendriveRoadSegm
         this->object.polygon.num_vertices++;
       }
     }
-    else if(object_info.outline().get().cornerLocal().size()>0)// local coordinates with respect to the object anchor point
+    else if(object_info.outline().get().cornerLocal().size()>0)// local coordinates with respect to the object anchor pose
     {
       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)
       {
@@ -124,9 +124,9 @@ double COpendriveObject::get_scale_factor(void)
   return this->scale_factor;
 }
 
-TOpendriveTrackPoint COpendriveObject::get_track_pose(void) const
+TOpendriveTrackPose COpendriveObject::get_track_pose(void) const
 {
-  TOpendriveTrackPoint track;
+  TOpendriveTrackPose track;
 
   track.s=this->pose.s/this->scale_factor;
   track.t=this->pose.t/this->scale_factor;
@@ -135,13 +135,13 @@ TOpendriveTrackPoint COpendriveObject::get_track_pose(void) const
   return track;
 }
 
-TOpendriveWorldPoint COpendriveObject::get_world_pose(void) const
+TOpendriveWorldPose COpendriveObject::get_world_pose(void) const
 {
-  TOpendriveWorldPoint world;
+  TOpendriveWorldPose world;
 
   if(this->segment!=NULL)
   {
-    world=segment->transform_to_world_point(this->get_track_pose());
+    world=segment->transform_to_world_pose(this->get_track_pose());
     return world;
   }
   else
diff --git a/src/opendrive_param_poly3.cpp b/src/opendrive_param_poly3.cpp
index d973be2..6405540 100644
--- a/src/opendrive_param_poly3.cpp
+++ b/src/opendrive_param_poly3.cpp
@@ -27,7 +27,7 @@ COpendriveParamPoly3::COpendriveParamPoly3(const COpendriveParamPoly3 &object) :
   this->normalized=object.normalized;
 }
 
-bool COpendriveParamPoly3::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const
+bool COpendriveParamPoly3::transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const
 {
   double p = (this->normalized ? track.s/((this->max_s - this->min_s)/this->scale_factor):track.s);
   double p2 = p*p;
diff --git a/src/opendrive_road.cpp b/src/opendrive_road.cpp
index aa29dee..6ca93c1 100644
--- a/src/opendrive_road.cpp
+++ b/src/opendrive_road.cpp
@@ -179,23 +179,23 @@ void COpendriveRoad::link_segments(OpenDRIVE &open_drive)
                 prev_road->link_segment(road,from_lane_id,false,-1,true);
               else 
                 prev_road->link_segment(road,from_lane_id,true,-1,true);
-              TOpendriveWorldPoint end=road->get_lane(-1).get_end_point();
-              TOpendriveWorldPoint start;
+              TOpendriveWorldPose end=road->get_lane(-1).get_end_pose();
+              TOpendriveWorldPose start;
               if(successor_contact=="end")
               {
                 if(to_lane_id<0)
-                  start=next_road->get_lane(to_lane_id).get_end_point();
+                  start=next_road->get_lane(to_lane_id).get_end_pose();
                 else
-                  start=next_road->get_lane(to_lane_id).get_start_point();
+                  start=next_road->get_lane(to_lane_id).get_start_pose();
                 if(fabs(end.x-start.x)<this->resolution && fabs(end.y-start.y)<this->resolution)
                   road->link_segment(next_road,-1,false,to_lane_id,false);
               }
               else
               {
                 if(to_lane_id<0)
-                  start=next_road->get_lane(to_lane_id).get_start_point();
+                  start=next_road->get_lane(to_lane_id).get_start_pose();
                 else
-                  start=next_road->get_lane(to_lane_id).get_end_point();
+                  start=next_road->get_lane(to_lane_id).get_end_pose();
                 if(fabs(end.x-start.x)<this->resolution && fabs(end.y-start.y)<this->resolution)
                   road->link_segment(next_road,-1,false,to_lane_id,true);
               }
@@ -282,7 +282,7 @@ bool COpendriveRoad::remove_lane(COpendriveLane *lane)
 void COpendriveRoad::complete_open_lanes(void)
 {
   std::vector<COpendriveLane *>::iterator lane_it;
-  TOpendriveWorldPoint end_point;
+  TOpendriveWorldPose end_pose;
 
   // remove all nodes and lanes not present in the path
   for(lane_it=this->lanes.begin();lane_it!=this->lanes.end();)
@@ -290,10 +290,10 @@ void COpendriveRoad::complete_open_lanes(void)
     if((*lane_it)->next.empty())// lane is not connected
     {
       try{
-        end_point=(*lane_it)->get_end_point();
-        if(!this->node_exists_at(end_point))// there is no node at the end point
+        end_pose=(*lane_it)->get_end_pose();
+        if(!this->node_exists_at(end_pose))// there is no node at the end pose
         {
-          (*lane_it)->segment->add_empty_node(end_point,(*lane_it));
+          (*lane_it)->segment->add_empty_node(end_pose,(*lane_it));
           (*lane_it)->segment->link_neightbour_lanes();
         }
         else
@@ -488,13 +488,13 @@ void COpendriveRoad::prune(std::vector<unsigned int> &path_nodes)
   } 
 }
 
-bool COpendriveRoad::node_exists_at(TOpendriveWorldPoint &pose)
+bool COpendriveRoad::node_exists_at(TOpendriveWorldPose &pose)
 {
-  TOpendriveWorldPoint node_pose;
+  TOpendriveWorldPose node_pose;
 
   for(unsigned int i=0;i<nodes.size();i++)
   {
-    node_pose=this->nodes[i]->get_point();
+    node_pose=this->nodes[i]->get_pose();
     if(std::abs(pose.x-node_pose.x)<0.01 && std::abs(pose.y-node_pose.y)<0.01)
       return true;
   }
@@ -502,13 +502,13 @@ bool COpendriveRoad::node_exists_at(TOpendriveWorldPoint &pose)
   return false;
 }
 
-COpendriveRoadNode* COpendriveRoad::get_node_at(TOpendriveWorldPoint &pose)
+COpendriveRoadNode* COpendriveRoad::get_node_at(TOpendriveWorldPose &pose)
 {
-  TOpendriveWorldPoint node_pose;
+  TOpendriveWorldPose node_pose;
 
   for(unsigned int i=0;i<nodes.size();i++)
   {
-    node_pose=this->nodes[i]->get_point();
+    node_pose=this->nodes[i]->get_pose();
     if(std::abs(pose.x-node_pose.x)<0.01 && std::abs(pose.y-node_pose.y)<0.01)
       return this->nodes[i];
   }
@@ -645,16 +645,16 @@ const COpendriveRoadSegment& COpendriveRoad::operator[](std::size_t index)
   }
 }
 
-unsigned int COpendriveRoad::get_closest_node(TOpendriveWorldPoint &point,double angle_tol)
+unsigned int COpendriveRoad::get_closest_node(TOpendriveWorldPose &pose,double angle_tol)
 {
   double dist,min_dist=std::numeric_limits<double>::max();
-  TOpendriveWorldPoint closest_point;
+  TOpendriveWorldPose closest_pose;
   unsigned int closest_index;
 
   for(unsigned int i=0;i<this->nodes.size();i++)
   { 
-    this->nodes[i]->get_closest_point(point,closest_point,angle_tol);
-    dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
+    this->nodes[i]->get_closest_pose(pose,closest_pose,angle_tol);
+    dist=sqrt(pow(closest_pose.x-pose.x,2.0)+pow(closest_pose.y-pose.y,2.0));
     if(dist<min_dist)
     { 
       min_dist=dist;
@@ -665,20 +665,20 @@ unsigned int COpendriveRoad::get_closest_node(TOpendriveWorldPoint &point,double
   return closest_index;
 }
 
-double COpendriveRoad::get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol)
+double COpendriveRoad::get_closest_pose(TOpendriveWorldPose &pose,TOpendriveWorldPose &closest_pose,double angle_tol)
 {
   double dist,min_dist=std::numeric_limits<double>::max();
-  TOpendriveWorldPoint point_found;
+  TOpendriveWorldPose pose_found;
   double length,closest_length;
 
   for(unsigned int i=0;i<this->nodes.size();i++)
   {
-    length=this->nodes[i]->get_closest_point(point,point_found,angle_tol);
-    dist=sqrt(pow(point_found.x-point.x,2.0)+pow(point_found.y-point.y,2.0));
+    length=this->nodes[i]->get_closest_pose(pose,pose_found,angle_tol);
+    dist=sqrt(pow(pose_found.x-pose.x,2.0)+pow(pose_found.y-pose.y,2.0));
     if(dist<min_dist)
     {
       min_dist=dist;
-      closest_point=point_found;
+      closest_pose=pose_found;
       closest_length=length;
     }
   }
@@ -686,25 +686,25 @@ double COpendriveRoad::get_closest_point(TOpendriveWorldPoint &point,TOpendriveW
   return closest_length;
 }
 
-void COpendriveRoad::get_closest_points(TOpendriveWorldPoint &point,std::vector<TOpendriveWorldPoint> &closest_points,std::vector<double> &closest_lengths,double dist_tol,double angle_tol)
+void COpendriveRoad::get_closest_poses(TOpendriveWorldPose &pose,std::vector<TOpendriveWorldPose> &closest_poses,std::vector<double> &closest_lengths,double dist_tol,double angle_tol)
 {
-  std::vector<TOpendriveWorldPoint> points;
+  std::vector<TOpendriveWorldPose> poses;
   std::vector<double> lengths;
 
-  closest_points.clear();
+  closest_poses.clear();
   closest_lengths.clear();
   for(unsigned int i=0;i<this->nodes.size();i++)
   {
-    this->nodes[i]->get_closest_points(point,points,lengths,dist_tol,angle_tol);
-    for(unsigned int j=0;j<points.size();i++)
+    this->nodes[i]->get_closest_poses(pose,poses,lengths,dist_tol,angle_tol);
+    for(unsigned int j=0;j<poses.size();i++)
     {
-      closest_points.push_back(points[i]);
+      closest_poses.push_back(poses[i]);
       closest_lengths.push_back(lengths[i]);
     }
   }
 }
 
-std::vector<unsigned int> COpendriveRoad::get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPoint &start_point,TOpendriveWorldPoint &end_point,COpendriveRoad &new_road)
+std::vector<unsigned int> COpendriveRoad::get_sub_road(std::vector<unsigned int> &path_nodes,TOpendriveWorldPose &start_pose,TOpendriveWorldPose &end_pose,COpendriveRoad &new_road)
 {
   segment_up_ref_t new_segment_ref;
   lane_up_ref_t new_lane_ref;
@@ -740,7 +740,7 @@ std::vector<unsigned int> COpendriveRoad::get_sub_road(std::vector<unsigned int>
   }
   // add the last segment
   node=this->nodes[path_nodes[path_nodes.size()-1]];
-  link_index=node->get_closest_link(end_point,3.14159);
+  link_index=node->get_closest_link(end_pose,3.14159);
   link=node->links[link_index];
   if(link==NULL)
     throw CException(_HERE_,"The provided path has unconnected nodes");
@@ -784,7 +784,7 @@ std::vector<unsigned int> COpendriveRoad::get_sub_road(std::vector<unsigned int>
   return new_path_nodes;
 }
 
-void COpendriveRoad::get_sub_road(TOpendriveWorldPoint &start_point,double length,COpendriveRoad &road)
+void COpendriveRoad::get_sub_road(TOpendriveWorldPose &start_pose,double length,COpendriveRoad &road)
 {
 
 }
diff --git a/src/opendrive_road_node.cpp b/src/opendrive_road_node.cpp
index d37638d..edfb351 100644
--- a/src/opendrive_road_node.cpp
+++ b/src/opendrive_road_node.cpp
@@ -7,9 +7,9 @@ COpendriveRoadNode::COpendriveRoadNode()
 {
   this->resolution=DEFAULT_RESOLUTION;
   this->scale_factor=DEFAULT_SCALE_FACTOR;
-  this->point.x=0.0;
-  this->point.y=0.0;
-  this->point.heading=0.0;
+  this->pose.x=0.0;
+  this->pose.y=0.0;
+  this->pose.heading=0.0;
   this->parents.clear();
   this->links.clear();
   this->index=-1;
@@ -21,7 +21,7 @@ COpendriveRoadNode::COpendriveRoadNode(const COpendriveRoadNode &object)
 
   this->resolution=object.resolution;
   this->scale_factor=object.scale_factor;
-  this->point=object.point;
+  this->pose=object.pose;
   this->parents.resize(object.parents.size());
   for(unsigned int i=0;i<object.parents.size();i++)
   {
@@ -40,7 +40,7 @@ COpendriveRoadNode::COpendriveRoadNode(const COpendriveRoadNode &object)
 
 bool COpendriveRoadNode::add_link(COpendriveRoadNode *node,opendrive_mark_t mark,COpendriveRoadSegment *segment,COpendriveLane *lane)
 {
-  TOpendriveWorldPoint lane_end,node_point;
+  TOpendriveWorldPose lane_end,node_pose;
   double start_curvature,end_curvature,length;
   COpendriveLink *new_link;
   bool lane_found=false;
@@ -56,12 +56,12 @@ bool COpendriveRoadNode::add_link(COpendriveRoadNode *node,opendrive_mark_t mark
   new_link->set_parent_segment(segment);
   new_link->set_parent_lane(lane);
   // get the curvature
-  node_point=node->get_point();
+  node_pose=node->get_pose();
   for(unsigned int i=0;i<this->parents.size();i++)
   {
     try{
-      lane_end=this->parents[i].lane->get_end_point();
-      if(fabs(lane_end.x-node_point.x)<this->resolution && fabs(lane_end.y-node_point.y)<this->resolution)
+      lane_end=this->parents[i].lane->get_end_pose();
+      if(fabs(lane_end.x-node_pose.x)<this->resolution && fabs(lane_end.y-node_pose.y)<this->resolution)
       {
         this->parents[i].geometry->get_curvature(start_curvature,end_curvature);
         length=this->parents[i].geometry->get_length();
@@ -81,7 +81,7 @@ bool COpendriveRoadNode::add_link(COpendriveRoadNode *node,opendrive_mark_t mark
   {
     start_curvature=0.0;
     end_curvature=0.0;
-    length=sqrt(pow(this->point.x-node_point.x,2.0)+pow(this->point.y-node_point.y,2.0));
+    length=sqrt(pow(this->pose.x-node_pose.x,2.0)+pow(this->pose.y-node_pose.y,2.0));
   }
   new_link->generate(start_curvature,end_curvature,length,lane_found);
   this->add_link(new_link);
@@ -163,9 +163,9 @@ void COpendriveRoadNode::set_index(unsigned int index)
   this->index=index;
 }
 
-void COpendriveRoadNode::set_point(TOpendriveWorldPoint &start)
+void COpendriveRoadNode::set_pose(TOpendriveWorldPose &start)
 {
-  this->point=start;
+  this->pose=start;
 }
 
 void COpendriveRoadNode::add_parent(const planView::geometry_type &geom_info,COpendriveLane *lane,COpendriveRoadSegment *segment)
@@ -246,7 +246,7 @@ void COpendriveRoadNode::free(void)
 
 void COpendriveRoadNode::load(const planView::geometry_type &geom_info,COpendriveLane *lane,COpendriveRoadSegment *segment)
 {
-  TOpendriveTrackPoint track_point;
+  TOpendriveTrackPose track_pose;
   COpendriveGeometry *geometry;
   std::stringstream text;
 
@@ -270,16 +270,16 @@ void COpendriveRoadNode::load(const planView::geometry_type &geom_info,COpendriv
   // import start position
   if(lane->get_id()<0)
   {
-    track_point.t=lane->get_offset()-lane->get_width()/2.0;
-    track_point.s=0.0;
+    track_pose.t=lane->get_offset()-lane->get_width()/2.0;
+    track_pose.s=0.0;
   }
   else
   {
-    track_point.t=lane->get_offset()+lane->get_width()/2.0;
-    track_point.s=geometry->get_length();
+    track_pose.t=lane->get_offset()+lane->get_width()/2.0;
+    track_pose.s=geometry->get_length();
   }
-  track_point.heading=0.0;
-  if(!geometry->get_world_pose(track_point,this->point))
+  track_pose.heading=0.0;
+  if(!geometry->get_world_pose(track_pose,this->pose))
   {
     delete geometry;
     text << "Impossible to get world coordinates " << segment->get_name() << " (lane " << lane->get_id() << ")"; 
@@ -288,7 +288,7 @@ void COpendriveRoadNode::load(const planView::geometry_type &geom_info,COpendriv
   else
   {
     if(lane->get_id()>0)
-      this->point.heading=normalize_angle(this->point.heading+3.14159);
+      this->pose.heading=normalize_angle(this->pose.heading+3.14159);
   }
   this->add_parent(geometry,lane,segment);
 }
@@ -360,7 +360,7 @@ void COpendriveRoadNode::clean_references(segment_up_ref_t &segment_refs,lane_up
   }
 }
 
-void COpendriveRoadNode::update_start_pose(COpendriveLane *lane,TOpendriveWorldPoint *start)
+void COpendriveRoadNode::update_start_pose(COpendriveLane *lane,TOpendriveWorldPose *start)
 {
   std::vector<TOpendriveRoadNodeParent>::iterator parent_it;
   std::vector<COpendriveLink *>::iterator link_it;
@@ -379,12 +379,12 @@ void COpendriveRoadNode::update_start_pose(COpendriveLane *lane,TOpendriveWorldP
     else
       parent_it++;
   }
-  length=this->get_closest_point(*start,this->point,3.14159);
+  length=this->get_closest_pose(*start,this->pose,3.14159);
   // update geometry 
   for(unsigned int i=0;i<this->parents.size();i++)
   {
     if(lane->get_id()<0)
-      this->parents[i].geometry->set_start_point(point);
+      this->parents[i].geometry->set_start_pose(pose);
     this->parents[i].geometry->set_max_s(this->parents[i].geometry->get_max_s()-length);
   }
   // update the links
@@ -403,11 +403,11 @@ void COpendriveRoadNode::update_start_pose(COpendriveLane *lane,TOpendriveWorldP
   }
 }
 
-void COpendriveRoadNode::update_end_pose(COpendriveLane *lane,TOpendriveWorldPoint *end)
+void COpendriveRoadNode::update_end_pose(COpendriveLane *lane,TOpendriveWorldPose *end)
 {
   std::vector<TOpendriveRoadNodeParent>::iterator parent_it;
   std::vector<COpendriveLink *>::iterator link_it;
-  TOpendriveWorldPoint end_point;
+  TOpendriveWorldPose end_pose;
   double length;
 
   if(end==NULL)
@@ -423,7 +423,7 @@ void COpendriveRoadNode::update_end_pose(COpendriveLane *lane,TOpendriveWorldPoi
     else
       parent_it++;
   }
-  length=this->get_closest_point(*end,end_point,3.14159);
+  length=this->get_closest_pose(*end,end_pose,3.14159);
   // update geometry 
   for(unsigned int i=0;i<this->parents.size();i++)
     this->parents[i].geometry->set_max_s(length);;
@@ -502,9 +502,9 @@ const COpendriveGeometry &COpendriveRoadNode::get_geometry(unsigned int index) c
   }
 }
 
-TOpendriveWorldPoint COpendriveRoadNode::get_point(void) const
+TOpendriveWorldPose COpendriveRoadNode::get_pose(void) const
 {
-  return this->point;
+  return this->pose;
 }
 
 unsigned int COpendriveRoadNode::get_num_links(void) const
@@ -539,22 +539,22 @@ const COpendriveLink &COpendriveRoadNode::get_link_ending_at(unsigned int node_i
   throw CException(_HERE_,text.str());
 }
 
-unsigned int COpendriveRoadNode::get_closest_link(TOpendriveWorldPoint &point,double angle_tol)const 
+unsigned int COpendriveRoadNode::get_closest_link(TOpendriveWorldPose &pose,double angle_tol)const 
 {
   double dist,min_dist=std::numeric_limits<double>::max();
   unsigned int closest_index=-1;
   double angle;
-  TOpendriveWorldPoint closest_point;
+  TOpendriveWorldPose closest_pose;
 
   for(unsigned int i=0;i<this->links.size();i++)
   {
     if(&this->links[i]->get_prev()==this)// links starting at this node
     {
-      this->links[i]->find_closest_world_point(point,closest_point);
-      angle=diff_angle(normalize_angle(point.heading),closest_point.heading);
+      this->links[i]->find_closest_world_pose(pose,closest_pose);
+      angle=diff_angle(normalize_angle(pose.heading),closest_pose.heading);
       if(fabs(angle)<angle_tol)
       {
-        dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
+        dist=sqrt(pow(closest_pose.x-pose.x,2.0)+pow(closest_pose.y-pose.y,2.0));
         if(dist<min_dist)
         {
           min_dist=dist;
@@ -567,21 +567,21 @@ unsigned int COpendriveRoadNode::get_closest_link(TOpendriveWorldPoint &point,do
   return closest_index;
 }
 
-double COpendriveRoadNode::get_closest_distance(TOpendriveWorldPoint &point,double angle_tol)const 
+double COpendriveRoadNode::get_closest_distance(TOpendriveWorldPose &pose,double angle_tol)const 
 {
   double dist,min_dist=std::numeric_limits<double>::max();
   double angle;
-  TOpendriveWorldPoint closest_point;
+  TOpendriveWorldPose closest_pose;
 
   for(unsigned int i=0;i<this->links.size();i++)
   {
     if(&this->links[i]->get_prev()==this)// links starting at this node
     {
-      this->links[i]->find_closest_world_point(point,closest_point);
-      angle=diff_angle(normalize_angle(point.heading),closest_point.heading);
+      this->links[i]->find_closest_world_pose(pose,closest_pose);
+      angle=diff_angle(normalize_angle(pose.heading),closest_pose.heading);
       if(fabs(angle)<angle_tol)
       {
-        dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
+        dist=sqrt(pow(closest_pose.x-pose.x,2.0)+pow(closest_pose.y-pose.y,2.0));
         if(dist<min_dist)
           min_dist=dist;
       }
@@ -591,24 +591,24 @@ double COpendriveRoadNode::get_closest_distance(TOpendriveWorldPoint &point,doub
   return min_dist;
 }
 
-double COpendriveRoadNode::get_closest_point(TOpendriveWorldPoint &point,TOpendriveWorldPoint &closest_point,double angle_tol) const
+double COpendriveRoadNode::get_closest_pose(TOpendriveWorldPose &pose,TOpendriveWorldPose &closest_pose,double angle_tol) const
 {
   double dist,min_dist=std::numeric_limits<double>::max();
   double angle;
   double length,closest_length=std::numeric_limits<double>::max();
 
-  closest_point.x=std::numeric_limits<double>::max();
-  closest_point.y=std::numeric_limits<double>::max();
-  closest_point.heading=std::numeric_limits<double>::max();
+  closest_pose.x=std::numeric_limits<double>::max();
+  closest_pose.y=std::numeric_limits<double>::max();
+  closest_pose.heading=std::numeric_limits<double>::max();
   for(unsigned int i=0;i<this->links.size();i++)
   {
     if(&this->links[i]->get_prev()==this)// links starting at this node
     {
-      length=this->links[i]->find_closest_world_point(point,closest_point);
-      angle=diff_angle(normalize_angle(point.heading),closest_point.heading);
+      length=this->links[i]->find_closest_world_pose(pose,closest_pose);
+      angle=diff_angle(normalize_angle(pose.heading),closest_pose.heading);
       if(fabs(angle)<angle_tol)
       {
-        dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
+        dist=sqrt(pow(closest_pose.x-pose.x,2.0)+pow(closest_pose.y-pose.y,2.0));
         if(dist<min_dist)
         {
           min_dist=dist;
@@ -621,27 +621,27 @@ double COpendriveRoadNode::get_closest_point(TOpendriveWorldPoint &point,TOpendr
   return closest_length;
 }
 
-void COpendriveRoadNode::get_closest_points(TOpendriveWorldPoint &point,std::vector<TOpendriveWorldPoint> &closest_points,std::vector<double> &closest_lengths,double dist_tol,double angle_tol) const
+void COpendriveRoadNode::get_closest_poses(TOpendriveWorldPose &pose,std::vector<TOpendriveWorldPose> &closest_poses,std::vector<double> &closest_lengths,double dist_tol,double angle_tol) const
 {
   double dist;
   double angle;
   double length;
-  TOpendriveWorldPoint closest_point;
+  TOpendriveWorldPose closest_pose;
 
-  closest_points.clear();
+  closest_poses.clear();
   closest_lengths.clear();
   for(unsigned int i=0;i<this->links.size();i++)
   {
     if(&this->links[i]->get_prev()==this)// links starting at this node
     {
-      length=this->links[i]->find_closest_world_point(point,closest_point);
-      angle=diff_angle(normalize_angle(point.heading),closest_point.heading);
+      length=this->links[i]->find_closest_world_pose(pose,closest_pose);
+      angle=diff_angle(normalize_angle(pose.heading),closest_pose.heading);
       if(fabs(angle)<angle_tol)
       {
-        dist=sqrt(pow(closest_point.x-point.x,2.0)+pow(closest_point.y-point.y,2.0));
+        dist=sqrt(pow(closest_pose.x-pose.x,2.0)+pow(closest_pose.y-pose.y,2.0));
         if(dist<=dist_tol)
         {
-          closest_points.push_back(closest_point);
+          closest_poses.push_back(closest_pose);
           closest_lengths.push_back(length);
         }
       }
@@ -652,7 +652,7 @@ void COpendriveRoadNode::get_closest_points(TOpendriveWorldPoint &point,std::vec
 std::ostream& operator<<(std::ostream& out, COpendriveRoadNode &node)
 {
   out << "    Node: " << node.get_index() << std::endl;
-  out << "      start point: x: " << node.point.x << " y: " << node.point.y << " heading: " << node.point.heading << std::endl;
+  out << "      start pose: x: " << node.pose.x << " y: " << node.pose.y << " heading: " << node.pose.heading << std::endl;
   out << "      Number of parent: " << node.get_num_parents() << std::endl;
   for(unsigned int i=0;i<node.get_num_parents();i++)
   {
@@ -673,9 +673,9 @@ COpendriveRoadNode::~COpendriveRoadNode()
 {
   this->resolution=DEFAULT_RESOLUTION;
   this->scale_factor=DEFAULT_SCALE_FACTOR;
-  this->point.x=0.0;
-  this->point.y=0.0;
-  this->point.heading=0.0;
+  this->pose.x=0.0;
+  this->pose.y=0.0;
+  this->pose.heading=0.0;
   this->free();
 }
 
diff --git a/src/opendrive_road_segment.cpp b/src/opendrive_road_segment.cpp
index 9f56769..80dc2bb 100644
--- a/src/opendrive_road_segment.cpp
+++ b/src/opendrive_road_segment.cpp
@@ -329,7 +329,7 @@ void COpendriveRoadSegment::add_nodes(OpenDRIVE::road_type &road_info)
 void COpendriveRoadSegment::add_node(const planView::geometry_type &geom_info,COpendriveLane *lane)
 {
   COpendriveRoadNode *new_node;
-  TOpendriveWorldPoint node_pose;
+  TOpendriveWorldPose node_pose;
   unsigned int node_index;
   bool exist=false;
 
@@ -340,7 +340,7 @@ void COpendriveRoadSegment::add_node(const planView::geometry_type &geom_info,CO
     new_node->load(geom_info,lane,this);
     if(new_node->get_geometry(0).get_length()>this->min_road_length)
     {
-      node_pose=new_node->get_point();
+      node_pose=new_node->get_pose();
       if(this->parent_road->node_exists_at(node_pose))
       {
         delete new_node;
@@ -370,7 +370,7 @@ void COpendriveRoadSegment::add_node(const planView::geometry_type &geom_info,CO
   }
 }
 
-void COpendriveRoadSegment::add_empty_node(TOpendriveWorldPoint &point,COpendriveLane *lane)
+void COpendriveRoadSegment::add_empty_node(TOpendriveWorldPose &pose,COpendriveLane *lane)
 {
   COpendriveRoadNode *new_node;
   unsigned int node_index;
@@ -380,7 +380,7 @@ void COpendriveRoadSegment::add_empty_node(TOpendriveWorldPoint &point,COpendriv
     new_node=new COpendriveRoadNode();
     new_node->set_resolution(this->resolution);
     new_node->set_scale_factor(this->scale_factor);
-    new_node->set_point(point);
+    new_node->set_pose(pose);
     node_index=this->parent_road->add_node(new_node);
     new_node->set_index(node_index);
     for(unsigned int i=0;i<this->nodes.size();i++)
@@ -585,7 +585,7 @@ bool COpendriveRoadSegment::connects_segments(COpendriveRoadSegment *segment1,CO
     return false;
 }
 
-COpendriveRoadSegment *COpendriveRoadSegment::get_sub_segment(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,int node_side,TOpendriveWorldPoint *start,TOpendriveWorldPoint *end)
+COpendriveRoadSegment *COpendriveRoadSegment::get_sub_segment(node_up_ref_t &new_node_ref,lane_up_ref_t &new_lane_ref,int node_side,TOpendriveWorldPose *start,TOpendriveWorldPose *end)
 {
   std::map<int,COpendriveLane *>::iterator lane_it;
   lane_up_ref_t::iterator lane_ref_it;
@@ -812,49 +812,49 @@ const COpendriveRoadSegment &COpendriveRoadSegment::get_connecting(unsigned int
   }
 }
 
-TOpendriveLocalPoint COpendriveRoadSegment::transform_to_local_point(const TOpendriveTrackPoint &track)
+TOpendriveLocalPose COpendriveRoadSegment::transform_to_local_pose(const TOpendriveTrackPose &track)
 {
-  TOpendriveTrackPoint point;
-  TOpendriveLocalPoint local;
+  TOpendriveTrackPose pose;
+  TOpendriveLocalPose local;
   std::stringstream error;
 
   if(track.s<0.0)
   {
-    error << "Invalid track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
+    error << "Invalid track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
     throw CException(_HERE_,error.str());
   }
-  point=track;
+  pose=track;
   if(this->num_right_lanes>0)
-    local=this->lanes[-1]->transform_to_local_point(point);
+    local=this->lanes[-1]->transform_to_local_pose(pose);
   else
   {
-    point.s=this->lanes[1]->get_length()-track.s;
-    point.heading=normalize_angle(track.heading+3.14159);
-    local=this->lanes[1]->transform_to_local_point(point);
+    pose.s=this->lanes[1]->get_length()-track.s;
+    pose.heading=normalize_angle(track.heading+3.14159);
+    local=this->lanes[1]->transform_to_local_pose(pose);
   }
 
   return local;
 }
 
-TOpendriveWorldPoint COpendriveRoadSegment::transform_to_world_point(const TOpendriveTrackPoint &track)
+TOpendriveWorldPose COpendriveRoadSegment::transform_to_world_pose(const TOpendriveTrackPose &track)
 {
-  TOpendriveTrackPoint point;
-  TOpendriveWorldPoint world;
+  TOpendriveTrackPose pose;
+  TOpendriveWorldPose world;
   std::stringstream error;
 
   if(track.s<0.0)
   {
-    error << "Invalid track point (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
+    error << "Invalid track pose (s=" << track.s << ",t=" << track.t << ",heading=" << track.heading << ")";
     throw CException(_HERE_,error.str());
   }
-  point=track;
+  pose=track;
   if(this->num_right_lanes>0)
-    world=this->lanes[-1]->transform_to_world_point(point);
+    world=this->lanes[-1]->transform_to_world_pose(pose);
   else
   {
-    point.s=this->lanes[1]->get_length()-track.s;
-    point.heading=normalize_angle(track.heading+3.14159);
-    world=this->lanes[1]->transform_to_world_point(point);
+    pose.s=this->lanes[1]->get_length()-track.s;
+    pose.heading=normalize_angle(track.heading+3.14159);
+    world=this->lanes[1]->transform_to_world_pose(pose);
   }
 
   return world;
diff --git a/src/opendrive_signal.cpp b/src/opendrive_signal.cpp
index d5d202a..bea1acd 100644
--- a/src/opendrive_signal.cpp
+++ b/src/opendrive_signal.cpp
@@ -69,9 +69,9 @@ double COpendriveSignal::get_scale_factor(void)
   return this->scale_factor;
 }
 
-TOpendriveTrackPoint COpendriveSignal::get_track_pose(void) const
+TOpendriveTrackPose COpendriveSignal::get_track_pose(void) const
 {
-  TOpendriveTrackPoint track;
+  TOpendriveTrackPose track;
  
   track.s=this->pose.s/this->scale_factor;
   track.t=this->pose.t/this->scale_factor;
@@ -80,13 +80,13 @@ TOpendriveTrackPoint COpendriveSignal::get_track_pose(void) const
   return track;
 }
 
-TOpendriveWorldPoint COpendriveSignal::get_world_pose(void) const
+TOpendriveWorldPose COpendriveSignal::get_world_pose(void) const
 {
-  TOpendriveWorldPoint world;
+  TOpendriveWorldPose world;
 
   if(this->segment!=NULL)
   {
-    world=segment->transform_to_world_point(this->get_track_pose());
+    world=segment->transform_to_world_pose(this->get_track_pose());
     return world;
   }
   else
@@ -111,7 +111,7 @@ std::string COpendriveSignal::get_text(void) const
 
 std::ostream& operator<<(std::ostream& out, COpendriveSignal &signal)
 {
-  TOpendriveTrackPoint track;
+  TOpendriveTrackPose track;
 
   out << "  Signal id = " << signal.id << std::endl;
   out << "    type = " << signal.type << "," << signal.sub_type << std::endl;
diff --git a/src/opendrive_spiral.cpp b/src/opendrive_spiral.cpp
index d11ac2b..1e21a50 100644
--- a/src/opendrive_spiral.cpp
+++ b/src/opendrive_spiral.cpp
@@ -12,7 +12,7 @@ COpendriveSpiral::COpendriveSpiral(const COpendriveSpiral &object) : COpendriveG
   this->end_curvature=object.end_curvature;
 }
 
-bool COpendriveSpiral::transform_local_pose(TOpendriveTrackPoint &track,TOpendriveLocalPoint &local) const
+bool COpendriveSpiral::transform_local_pose(TOpendriveTrackPose &track,TOpendriveLocalPose &local) const
 {
   return true;
 }
-- 
GitLab