diff --git a/include/adc_circuit.h b/include/adc_circuit.h
index 9189e8d09e79cae43e0a7a8f4e6cd010df3723a2..d6eafd222b9b68802bb9f001c393df9072bc40ef 100644
--- a/include/adc_circuit.h
+++ b/include/adc_circuit.h
@@ -6,19 +6,88 @@
 #include "adc_road.h"
 #include <vector>
 
+
+/**
+ * \class CAdcCircuit
+ *
+ * \brief Class to store all the useful information of a OpenDrive circuit.
+ *
+ * It has access to each road information.
+ *
+ */
 class CAdcCircuit
 {
   private:
-    std::vector<CAdcRoad> roads;
+    std::vector<CAdcRoad> roads;///< Variable to store an access each road data.
+
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcCircuit();
+
+    /**
+     * \brief Default destructor.
+     *
+     * It deletes each road geometry pointer.
+     *  
+     */
     ~CAdcCircuit();
 
+    /**
+     * \brief Function to clear roads.
+     *
+     */
     void clear_roads(void);
+
+    /**
+     * \brief Function to add a road.
+     *
+     * \param road The road to add.
+     *
+     */
     void add_road(CAdcRoad &road);
+
+    /**
+     * \brief Function to print each road info.
+     *
+     * It calls CAdcRoad::debug function of each road.
+     *
+     */
     void debug(void);
+
+    /**
+     * \brief Function to calculate the world pose of each sign.
+     *
+     * It calls CAdcRoad::calculate_signals_pose function of each road.
+     *
+     * \param debug Boolean to print all the information stored on each signal at 
+     * the end of the function.
+     */
     void calculate_signals_pose(bool debug = false);
+
+    /**
+     * \brief Function to get all the signs presents on circuit.
+     *
+     * It calls CAdcRoad::get_signals function of each road.
+     *
+     * \param signals Variable to store the information.
+     */
     void get_signals(std::vector<CAdcSignals> &signals);
+
+    /**
+     * \brief Function to generate a .launch to spwan all
+     * the recognized signs.
+     *
+     * First it saves the header of the file. Secondly it
+     * calls CAdcRoad::append_signs_spwan. Finally, it saves
+     * the end of the launch file.
+     *
+     * \param filename The route to the output .launch file.
+     *
+     * \throws CException If the output file can't be opened.
+     */
     void generate_spwan_launch_file(std::string &filename);
 };
 
diff --git a/include/adc_geometries.h b/include/adc_geometries.h
index 9ff6ae3c8e4d8b4670aee1108d725304d82c581b..f417953cd7a5b953f007d52ecf0f1e5287160115 100644
--- a/include/adc_geometries.h
+++ b/include/adc_geometries.h
@@ -1,78 +1,396 @@
 #ifndef _ADC_GEOMETRIES_H
 #define _ADC_GEOMETRIES_H
 
-
+/**
+ * \class CAdcGeometry
+ *
+ * \brief Base class to store the common information of all road geometries.
+ *
+ * It's a pure abstract class that defines two pure virtual member functions.
+ *
+ */
 class CAdcGeometry
 {
   private:
   protected:
-    double min_s;
-    double max_s;
-    double x;
-    double y;
-    double heading;
+    double min_s; ///< Starting track coordenate "s" for the geometry.
+    double max_s; ///< Ending track coordenate "s" for the geometry.
+    double x; ///< World x coordenate for the geometry origin.
+    double y; ///< World y coordenate for the geometry origin.
+    double heading;  ///< World heading for the geometry origin.
 
+    /**
+     * \brief Pure virtual function to print specific geometry type info.
+     *
+     */
     virtual void debug_param(void) = 0;
+
+    /**
+     * \brief Pure virtual function to transform from track coordenatos to local coordenates.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     virtual bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw) = 0;
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeometry();
+
+    /**
+     * \brief Class constructor.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *
+     */
     CAdcGeometry(double min_s, double max_s, double x, double y, double heading);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     virtual ~CAdcGeometry();
 
+    /**
+     * \brief Function to transform from track coordenatos to world coordenates.
+     *
+     * It calls CAdcGeometry::get_local_pose pure virtual funciton to calculate the local coordenates.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param x Output for the world x coordenate.
+     *
+     * \param y Output for the world y coordenate.
+     *
+     * \param yaw Output for the world yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_world_pose(double s, double t, double heading, double &x, double &y, double &yaw);
+
+    /**
+     * \brief Function to check if an element belongs to this geometry.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \return If belongs or not.
+     *
+     */
     bool on_range(double s);
+
+    /**
+     * \brief Function to print its info.
+     *
+     * It calls CAdcGeometry::debug_param virtual functions.
+     *
+     */
     void debug(void);
 };
 
+
+/**
+ * \class CAdcGeoLine
+ *
+ * \brief Class to store the specific data of a Line geometry.
+ *
+ * It's a CAdcGeometry derived class.
+ *
+ */
 class CAdcGeoLine: public CAdcGeometry
 {
   private:
   protected:
+
+    /**
+     * \brief Function to print specific geometry type info.
+     *
+     */
     void debug_param(void);
+
+    /**
+     * \brief Function to transform from track coordenatos to local coordenates.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw);
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeoLine();
+
+    /**
+     * \brief Class constructor with the common geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *  
+     */
     CAdcGeoLine(double min_s, double max_s, double x, double y, double heading);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcGeoLine();
 };
 
+
+/**
+ * \class CAdcGeoSpiral
+ *
+ * \brief Class to store the specific data of a Spiral geometry.
+ *
+ * It's a CAdcGeometry derived class.
+ *
+ */
 class CAdcGeoSpiral: public CAdcGeometry
 {
   private:
-    double curv_start;
-    double curv_end;
+    double curv_start; ///< Initial curvature
+    double curv_end; ///< End curvature
 
   protected:
+    /**
+     * \brief Function to print specific geometry type info.
+     *
+     */
     void debug_param(void);
+
+    /**
+     * \brief Function to transform from track coordenatos to local coordenates.
+     *
+     * ----------------Not supported------------------------
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw);
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeoSpiral();
+
+    /**
+     * \brief Class constructor with the common geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *  
+     */
     CAdcGeoSpiral(double min_s, double max_s, double x, double y, double heading);
+
+    /**
+     * \brief Class constructor with the common and specific geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *
+     * \param curv_start Spiral initial curvature.
+     *
+     * \param curv_end Spiral end curvature.
+     *  
+     */
     CAdcGeoSpiral(double min_s, double max_s, double x, double y, double heading, double curv_start, double curv_end);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcGeoSpiral();
+
+    /**
+     * \brief Fu nction to seet the specific geometry parameters.
+     *
+     * \param curv_start Spiral initial curvature.
+     *
+     * \param curv_end Spiral end curvature.
+     *  
+     */
     void set_params(double curv_start, double curv_end);
 };
 
+
+/**
+ * \class CAdcGeoArc
+ *
+ * \brief Class to store the specific data of a Arc geometry.
+ *
+ * It's a CAdcGeometry derived class.
+ *
+ */
 class CAdcGeoArc: public CAdcGeometry
 {
   private:
-    double curvature;
+    double curvature; ///< Curvature
 
   protected:
+    /**
+     * \brief Function to print specific geometry type info.
+     *
+     */
     void debug_param(void);
+
+    /**
+     * \brief Function to transform from track coordenatos to local coordenates.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw);
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeoArc();
+
+    /**
+     * \brief Class constructor with the common geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *  
+     */
     CAdcGeoArc(double min_s, double max_s, double x, double y, double heading);
+    /**
+     * \brief Class constructor with the common and specific geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *
+     * \param curvature Arc curvature.
+     *  
+     */
     CAdcGeoArc(double min_s, double max_s, double x, double y, double heading, double curvature);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcGeoArc();
+
+    /**
+     * \brief Fu nction to seet the specific geometry parameters.
+     *
+     * \param curvature Arc curvature.
+     *  
+     */
     void set_params(double curvature);
 };
 
+
+/**
+ * \struct Adc_poly3_param.
+ *
+ * \brief A struct with the four parameters to define a poly3 geometry.
+ */
 typedef struct 
 {
   double a;
@@ -81,39 +399,208 @@ typedef struct
   double d;
 }Adc_poly3_param;
 
+
+/**
+ * \class CAdcGeoPoly3
+ *
+ * \brief Class to store the specific data of a Poly3 geometry.
+ *
+ * It's a CAdcGeometry derived class.
+ *
+ */
 class CAdcGeoPoly3: public CAdcGeometry
 {
   private:
-    Adc_poly3_param param;
+    Adc_poly3_param param; ///< Poly3 parameters
 
   protected:
+    /**
+     * \brief Function to print specific geometry type info.
+     *
+     */
     void debug_param(void);
+
+    /**
+     * \brief Function to transform from track coordenatos to local coordenates.
+     *
+     * ----------------Not supported------------------------
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw);
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeoPoly3();
+
+    /**
+     * \brief Class constructor with the common geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *  
+     */
     CAdcGeoPoly3(double min_s, double max_s, double x, double y, double heading);
+    /**
+     * \brief Class constructor with the common and specific geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *
+     * \param param Poly3 params.
+     *  
+     */
     CAdcGeoPoly3(double min_s, double max_s, double x, double y, double heading, Adc_poly3_param param);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcGeoPoly3();
+
+    /**
+     * \brief Fu nction to seet the specific geometry parameters.
+     *
+     * \param param Poly3 params.
+     *  
+     */
     void set_params(Adc_poly3_param param);
 };
 
+
+/**
+ * \class CAdcGeoParamPoly3
+ *
+ * \brief Class to store the specific data of a ParamPoly3 geometry.
+ *
+ * It's a CAdcGeometry derived class.
+ *
+ */
 class CAdcGeoParamPoly3: public CAdcGeometry
 {
   private:
-    Adc_poly3_param u_param;
-    Adc_poly3_param v_param;
-    bool normalized;
+    Adc_poly3_param u_param; ///< Poly3 U parameters
+    Adc_poly3_param v_param; ///< Poly3 V parameters
+    bool normalized;  ///< If the parameter is normalized.
 
   protected:
+    /**
+     * \brief Function to print specific geometry type info.
+     *
+     */
     void debug_param(void);
+
+    /**
+     * \brief Function to transform from track coordenatos to local coordenates.
+     *
+     * \param s Track coordenate "s" of the element.
+     *
+     * \param t Track coordenate "t" of the element.
+     *
+     * \param heading Track heading of the element.
+     *
+     * \param u Output for the local u coordenate.
+     *
+     * \param v Output for the local v coordenate.
+     *
+     * \param yaw Output for the local yaw.
+     *
+     * \return True if successful.
+     *
+     */
     bool get_local_pose(double s, double t, double heading, double &u, double &v, double &yaw);
 
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcGeoParamPoly3();
+
+    /**
+     * \brief Class constructor with the common geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *  
+     */
     CAdcGeoParamPoly3(double min_s, double max_s, double x, double y, double heading);
+
+    /**
+     * \brief Class constructor with the common and specific geometry parameters.
+     *  
+     * \param min_s Geometry's min_s.
+     *
+     * \param max_s Geometry's max_s.
+     *
+     * \param x Geometry's origin x coordenate.
+     *
+     * \param y Geometry's origin y coordenate.
+     *
+     * \param heading Geometry's origins heading.
+     *
+     * \param u_param Poly3 U params.
+     *
+     * \param v_param Poly3 V params.
+     *
+     * \param normalized If is noramlized.
+     *  
+     */
     CAdcGeoParamPoly3(double min_s, double max_s, double x, double y, double heading, Adc_poly3_param u_param, Adc_poly3_param v_param, bool normalized = true);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcGeoParamPoly3();
+
+    /**
+     * \brief Fu nction to seet the specific geometry parameters.
+     *
+     * \param u_param Poly3 U params.
+     *
+     * \param v_param Poly3 V params.
+     *
+     * \param normalized If is noramlized.
+     *  
+     */
     void set_params(Adc_poly3_param u_param, Adc_poly3_param v_param, bool normalized = true);
 };
 #endif
\ No newline at end of file
diff --git a/include/adc_road.h b/include/adc_road.h
index c3ca57130140cfb308907f5c4d019169c2490ab9..2cb53c684fc23bb05e789632cd153532924ca534 100644
--- a/include/adc_road.h
+++ b/include/adc_road.h
@@ -7,31 +7,149 @@
 #include "adc_signals.h"
 
 
+/**
+ * \class CAdcRoad
+ *
+ * \brief Class to store all the useful information of a OpenDrive road.
+ *
+ * It has access to each geometry and signal belonging to the road.
+ *
+ */
 class CAdcRoad
 {
   private:
-    int id;
-    std::string name;
-    double length;
-    std::vector<CAdcGeometry*> geometries;
-    std::vector<CAdcSignals> signals;
+    int id; ///< Road's unique ID.
+    std::string name; ///< Road's name.
+    double length;///< Road's length.
+    std::vector<CAdcGeometry*> geometries;///< Road's geometries.
+    std::vector<CAdcSignals> signals; ///< Road's signals.
+
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     CAdcRoad();
+
+    /**
+     * \brief Default constructor.
+     *  
+     * \param id Road's id.
+     *
+     * \param length Road's length.
+     *
+     * \param name Road's name.
+     *
+     */
     CAdcRoad(int id, double length, std::string name);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcRoad();
 
+    /**
+     * \brief Function to clear geometries.
+     *
+     */
     void clear_geometries(void);
+
+    /**
+     * \brief Function to add a geometry.
+     *
+     * \param geometry The road's geometry to add.
+     *
+     */
     void add_geometry(CAdcGeometry* geometry);
+
+    /**
+     * \brief Function to delete all geometry pointers.
+     *
+     */
     void delete_geometries(void);
+
+    /**
+     * \brief Function to clear signals.
+     *
+     */
     void clear_signals(void);
+
+    /**
+     * \brief Function to add a sign.
+     *
+     * \param sign The road's sign to add.
+     *
+     */
     void add_signal(CAdcSignals sign);
+
+    /**
+     * \brief Function to set road's id.
+     *
+     * \param id The road's id.
+     *
+     */
     void set_id(int id);
+
+    /**
+     * \brief Function to get road's id.
+     *
+     * \return The road's id.
+     *
+     */
     int get_id(void);
+
+    /**
+     * \brief Function to set road's length.
+     *
+     * \param length The road's length.
+     *
+     */
     void set_length(double length);
+
+    /**
+     * \brief Function to get road's length.
+     *
+     * \return The road's length.
+     *
+     */
     double get_length(void);
+
+    /**
+     * \brief Function to print each geometry and signal info.
+     *
+     * It calls CAdcGeometry::debug and CAdcSignals::debug functions.
+     *
+     */
     void debug(void);
+
+    /**
+     * \brief Function to calculate the world pose of each sign.
+     *
+     * For each sign, it gets its track pose and check on wich
+     * geometry it belongs. After that it calculates its local pose and
+     * finally, the worl pose.
+     *
+     * \param debug Boolean to print all the information stored on each signal at 
+     * the end of the function.
+     */
     void calculate_signals_pose(bool debug = false);
+
+    /**
+     * \brief Function to get all the signs presents on circuit.
+     *
+     * \param signals Variable to store the information.
+     */
     void get_signals(std::vector<CAdcSignals> &signals);
+
+    /**
+     * \brief Function to append each sign spwan lines on a .launch file.
+     *
+     * It calls CAdcSignals::append_signs_spawn function.
+     *
+     * \param filename The route to the output .launch file.
+     *
+     */
     void append_signs_spawn(std::string &filename);
 };
 
diff --git a/include/adc_signals.h b/include/adc_signals.h
index 288553e9370d1a0059e4e9d02f2d96980969a44f..ad7161ae35efde05128d4088e603fe4d67f1d085 100644
--- a/include/adc_signals.h
+++ b/include/adc_signals.h
@@ -36,38 +36,149 @@
 #define SEMAPHORE_TYPE "1000001"
 #define SEMAPHORE_MARKER "alvar15"
 
+
+/**
+ * \struct Sign_urdf_info.
+ *
+ * \brief A struct with the marker and type names of a sign.
+ */
 typedef struct
 {
   std::string type;
   std::string marker;
 }Sign_urdf_info;
 
+
+/**
+ * \class CAdcSignals
+ *
+ * \brief Class to store the data of a signal.
+ *
+ */
+
 class CAdcSignals
 {
   private:
-    int id;
-    double s;
-    double t;
-    double heading;
-    double world_x;
-    double world_y;
-    double world_yaw;
-    std::string type;
-    std::string sub_type;
-    int value;
-    std::string text;
-    static std::map<std::string, Sign_urdf_info> urdf_map;
+    int id; ///< Signal's id.
+    double s; ///< Signal's track coordenate "s".
+    double t; ///< Signal's track coordenate "t".
+    double heading; ///< Signal's track heading.
+    double world_x; ///< Signal's world coordenate "x".
+    double world_y; ///< Signal's world coordenate "y".
+    double world_yaw; ///< Signal's world yaw.
+    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.
+    static std::map<std::string, Sign_urdf_info> urdf_map; ///< Static map to link OpenDrive types with sign_urdf_info.
+
+    /**
+     * \brief Static function to initialize urdf_map.
+     *  
+     * If urdf_map size is bigger tan 0 it doesn't do anything.
+     */
     static void set_urdf_map(void);
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     * It calls CAdcSignals::set_urdf_map function.
+     *
+     */
     CAdcSignals();
+
+    /**
+     * \brief Class constructor.
+     *  
+     * It calls CAdcSignals::set_urdf_map function.
+     *
+     * \param id Signal's id.
+     *
+     * \param s Signal's track coordenate "s".
+     *
+     * \param t Signal's track coordenate "t".
+     *
+     * \param heading Signal's track heading.
+     *
+     * \param type Signal's OpenDrive type.
+     *
+     * \param sub_type Signal's OpenDrive subtype.
+     *
+     * \param value Signal's value.
+     *
+     * \param text Signal's text.
+     *
+     * \param reverse boolean to add pi to the heading or not.
+     *  
+     */
     CAdcSignals(int id, double s, double t, double heading, std::string type, std::string sub_type, int value, std::string text, bool reverse = false);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~CAdcSignals();
 
+    /**
+     * \brief Function to get signal's id.
+     *  
+     * \return Signal's id.
+     *
+     */
     int get_id(void);
+
+    /**
+     * \brief Function to get signal's track pose.
+     *  
+     * \param s Output Signal's track coordenate "s".
+     *  
+     * \param t Output Signal's track coordenate "t".
+     *  
+     * \param heading Output Signal's track heading.
+     *
+     */
     void get_pose(double &s, double &t, double &heading);
+
+    /**
+     * \brief Function to get signal's info.
+     *  
+     * \param type Signal's OpenDrive type.
+     *
+     * \param sub_type Signal's OpenDrive subtype.
+     *
+     * \param value Signal's value.
+     *
+     * \param text Signal's text.
+     *
+     */
     void get_sign_info(std::string &type, std::string &sub_type, int &value, std::string &text);
+
+    /**
+     * \brief Function to set signal's world pose.
+     *  
+     * \param x Signal's world coordenate "x".
+     *  
+     * \param y Signal's world coordenate "y".
+     *  
+     * \param yaw Signal's world yaw.
+     *
+     */
     void set_world_pose(double x, double y, double yaw);
+
+    /**
+     * \brief Function to print its info.
+     *
+     * \param world_pose To print world pose or not.
+     *
+     */
     void debug(bool world_pose = false);
+
+    /**
+     * \brief Function to append each sign spwan lines on a .launch file.
+     *
+     * \param filename The route to the output .launch file.
+     *
+     */
     void append_sign_spawn(std::string &filename);
 };
 
diff --git a/include/open_drive_format.h b/include/open_drive_format.h
index 0fa1aa0721eae2d76bdb61192b2d64860d55cc30..fb8c0a9ffedc94b810c54788d16a8e819c9ec01d 100644
--- a/include/open_drive_format.h
+++ b/include/open_drive_format.h
@@ -6,17 +6,73 @@
 #include "adc_circuit.h"
 #include "adc_signals.h"
 
+
+/**
+ * \class COpenDriveFormat
+ *
+ * \brief Class to store and use the information on a .xodr file with OpenDrive 1.4 standar.
+ *
+ */
 class COpenDriveFormat
 {
   public:
+    /**
+     * \brief Default constructor.
+     *  
+     */
     COpenDriveFormat();
+
+    /**
+     * \brief Function to store on adc_circuit the useful information of a .xodr file.
+     *  
+     * If an optional parameter is not present, It will store a 0 or a "".
+     *
+     * \param filename The route to the .xodr file.
+     *
+     * \param debug Boolean to print all the information stored.
+     *
+     */
     void load(std::string &filename, bool debug = false);
+
+    /**
+     * \brief Function to calculate the world pose of each sign.
+     *
+     * It calls CAdcCircuit::calculate_signals_pose function.
+     *
+     * \param debug Boolean to print all the information stored on each signal at 
+     * the end of the function.
+     *
+     */
     void calculate_signals_pose(bool debug = false);
+
+    /**
+     * \brief Function to get all the signs presents on circuit.
+     *
+     * It calls CAdcCircuit::get_signals function.
+     *
+     * \param signals Variable to store the information.
+     *
+     */
     void get_signals(std::vector<CAdcSignals> &signals);
+
+    /**
+     * \brief Function to generate a .launch to spwan all
+     * the recognized signs.
+     *
+     * It calls CAdcCircuit::generate_spwan_launch_file function.
+     *
+     * \param filename The route to the output .launch file.
+     *
+     */
     void generate_spwan_launch_file(std::string &filename);
+
+    /**
+     * \brief Default destructor.
+     *  
+     */
     ~COpenDriveFormat();
    private:
-    CAdcCircuit adc_circuit;
+    CAdcCircuit adc_circuit; ///< Variable to store and access to the circuit information.
 };
 
 #endif
diff --git a/src/open_drive_format.cpp b/src/open_drive_format.cpp
index a17ba5b24c56e1ade4dcc24b68f3d7259391e2fd..40e2449af6d6717a334f79c16ef39d7cd1e54e36 100644
--- a/src/open_drive_format.cpp
+++ b/src/open_drive_format.cpp
@@ -156,6 +156,11 @@ void COpenDriveFormat::generate_spwan_launch_file(std::string &filename)
   this->adc_circuit.generate_spwan_launch_file(filename);
   std::cout << "Generating " << filename << " done" << std::endl;
 }
+
+COpenDriveFormat::~COpenDriveFormat()
+{
+}
+
 // void COpenDriveFormat::load(std::string &filename)
 // {
 //   struct stat buffer;
@@ -340,7 +345,4 @@ void COpenDriveFormat::generate_spwan_launch_file(std::string &filename)
 //     throw CException(_HERE_,"The configuration file does not exist");
 // }
  
-COpenDriveFormat::~COpenDriveFormat()
-{
-}