diff --git a/include/wolf_subscriber_gnss.h b/include/wolf_subscriber_gnss.h
index 0fa6531b0951fa7560f065444cfa8d6055181029..de3a920f77e81b74b13c98f42d56874c01e9c430 100644
--- a/include/wolf_subscriber_gnss.h
+++ b/include/wolf_subscriber_gnss.h
@@ -26,13 +26,13 @@
 /**************************
  *    WOLF-ROS includes   *
  **************************/
-#include "wolf_ros_subscriber.h"
+#include "wolf_subscriber.h"
 #include "subscriber_factory.h"
 #include "gnss_utils/gnss_utils.h"
 
 using namespace wolf;
 
-class SubscriberWrapperGnss : public SubscriberWrapper
+class WolfSubscriberGnss : public WolfSubscriber
 {
     protected:
 
@@ -47,7 +47,7 @@ class SubscriberWrapperGnss : public SubscriberWrapper
 
     public:
         // Constructor
-        SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr);
+        WolfSubscriberGnss(const SensorBasePtr& sensor_ptr);
 
         virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
 
@@ -55,6 +55,6 @@ class SubscriberWrapperGnss : public SubscriberWrapper
 
         void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg);
 
-        static std::shared_ptr<SubscriberWrapper> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
+        static std::shared_ptr<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
 };
-WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnss)
+WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnss)
diff --git a/include/wolf_subscriber_gnss_TDCP.h b/include/wolf_subscriber_gnss_TDCP.h
index 0349dce65b6a0542127a99daa4c940ab78f99d75..145a48b289961271c0d5c40ec0cd058772b50951 100644
--- a/include/wolf_subscriber_gnss_TDCP.h
+++ b/include/wolf_subscriber_gnss_TDCP.h
@@ -26,13 +26,13 @@
 /**************************
  *    WOLF-ROS includes   *
  **************************/
-#include "wolf_ros_subscriber.h"
+#include "wolf_subscriber.h"
 #include "subscriber_factory.h"
 #include "gnss_utils/gnss_utils.h"
 
 using namespace wolf;
 
-class SubscriberWrapperGnssTDCP : public SubscriberWrapper
+class WolfSubscriberGnssTDCP : public WolfSubscriber
 {
     protected:
 
@@ -44,7 +44,7 @@ class SubscriberWrapperGnssTDCP : public SubscriberWrapper
 
     public:
         // Constructor
-        SubscriberWrapperGnssTDCP(const SensorBasePtr& sensor_ptr);
+        WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr);
 
         virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
 
@@ -52,6 +52,6 @@ class SubscriberWrapperGnssTDCP : public SubscriberWrapper
 
         void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg);
 
-        static std::shared_ptr<SubscriberWrapper> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
+        static std::shared_ptr<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
 };
-WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnssTDCP)
+WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssTDCP)
diff --git a/include/wolf_subscriber_gnss_fix.h b/include/wolf_subscriber_gnss_fix.h
index 7140e6d98405d25cfda1694ec98a228b9c95856a..2a16a5f1bba570292812770344492f3444ae1095 100644
--- a/include/wolf_subscriber_gnss_fix.h
+++ b/include/wolf_subscriber_gnss_fix.h
@@ -24,7 +24,7 @@
 /**************************
  *    WOLF-ROS includes   *
  **************************/
-#include "wolf_ros_subscriber.h"
+#include "wolf_subscriber.h"
 #include "subscriber_factory.h"
 #include "gnss_utils/gnss_utils.h"
 
@@ -40,6 +40,6 @@ class WolfSubscriberGnssFix : public WolfSubscriber
 
         void callback(const sensor_msgs::NavSatFix::ConstPtr& msg);
 
-        static std::shared_ptr<SubscriberWrapper> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
+        static std::shared_ptr<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
 };
 WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssFix)
diff --git a/src/wolf_subscriber_gnss.cpp b/src/wolf_subscriber_gnss.cpp
index 1ddc25f394627c18d05bf22ede1e31ded50b745d..0030098534219359619535428c6c12f9c5c8c8c8 100644
--- a/src/wolf_subscriber_gnss.cpp
+++ b/src/wolf_subscriber_gnss.cpp
@@ -3,8 +3,8 @@
 using namespace wolf;
 
 // Constructor
-SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) :
-        Subscriber(sensor_ptr)
+WolfSubscriberGnss::WolfSubscriberGnss(const SensorBasePtr& sensor_ptr) :
+        WolfSubscriber(sensor_ptr)
 {
     //prcopt_ = prcopt_default;
     //prcopt_.mode = PMODE_SINGLE;
@@ -22,14 +22,14 @@ SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) :
 }
 
 
-void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
+void WolfSubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_     = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnss::callbackObservation, this);
-    sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnss::callbackNavigation, this);
+    sub_     = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnss::callbackObservation, this);
+    sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnss::callbackNavigation, this);
 }
 
 
-void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg)
+void WolfSubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg)
 {
     ROS_INFO("callbackObs!");
     if (last_nav_ptr_==nullptr)
@@ -44,7 +44,7 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const
     new_capture->process();
 }
 
-void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg)
+void WolfSubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg)
 {
     ROS_INFO("callbackNav!");
 
@@ -61,7 +61,7 @@ void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPt
 //    }
 }
 
-std::shared_ptr<Subscriber> SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
+std::shared_ptr<WolfSubscriber> WolfSubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
 {
-    return std::make_shared<SubscriberGnss>(_sensor_ptr);
+    return std::make_shared<WolfSubscriberGnss>(_sensor_ptr);
 }
diff --git a/src/wolf_subscriber_gnss_TDCP.cpp b/src/wolf_subscriber_gnss_TDCP.cpp
index 42bd270211be6f9e4fff31471b47941f330a2d16..e70df9e2f73d189d9513eb471a478a3486c7ac4f 100644
--- a/src/wolf_subscriber_gnss_TDCP.cpp
+++ b/src/wolf_subscriber_gnss_TDCP.cpp
@@ -3,19 +3,19 @@
 using namespace wolf;
 
 // Constructor
-SubscriberGnssTDCP::SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) :
-        Subscriber(sensor_ptr)
+WolfSubscriberGnssTDCP::WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) :
+        WolfSubscriber(sensor_ptr)
 {
     // TODO copied from TDCP_ros
 }
 
-void SubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
+void WolfSubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_     = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTDCP::callbackObservation, this);
-    sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTDCP::callbackNavigation, this);
+    sub_     = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnssTDCP::callbackObservation, this);
+    sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnssTDCP::callbackNavigation, this);
 }
 
-void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg)
+void WolfSubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg)
 {
     ROS_INFO("callbackObs!");
     if (last_nav_ptr_==nullptr)
@@ -33,7 +33,7 @@ void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::C
 //
 }
 
-void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg)
+void WolfSubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg)
 {
     ROS_INFO("callbackNav!");
 
@@ -44,7 +44,7 @@ void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::Con
     // TODO copied from TDCP_ros
 }
 
-std::shared_ptr<Subscriber> SubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
+std::shared_ptr<WolfSubscriber> WolfSubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
 {
-    return std::make_shared<SubscriberGnssTDCP>(_sensor_ptr);
+    return std::make_shared<WolfSubscriberGnssTDCP>(_sensor_ptr);
 }
diff --git a/src/wolf_subscriber_gnss_fix.cpp b/src/wolf_subscriber_gnss_fix.cpp
index 95c648abdfbfd6db86cea85a2cc1829f88d15034..0587ed8ae0ca7c6b86bcf32cd6d6ea42f0b6fad3 100644
--- a/src/wolf_subscriber_gnss_fix.cpp
+++ b/src/wolf_subscriber_gnss_fix.cpp
@@ -3,18 +3,18 @@
 using namespace wolf;
 
 // Constructor
-SubscriberGnssFix::SubscriberGnssFix(const SensorBasePtr& sensor_ptr) :
-        Subscriber(sensor_ptr)
+WolfSubscriberGnssFix::WolfSubscriberGnssFix(const SensorBasePtr& sensor_ptr) :
+        WolfSubscriber(sensor_ptr)
 {
 }
 
 
-void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
+void WolfSubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_     = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this);
+    sub_     = nh.subscribe(topic, 1, &WolfSubscriberGnssFix::callback, this);
 }
 
-void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg)
+void WolfSubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg)
 {
     Eigen::Matrix3d cov = Eigen::Map<const Eigen::Matrix3d>(msg->position_covariance.data());
 
@@ -27,7 +27,7 @@ void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg)
                                                                       false); // false = {LatLonAlt fix and ENU cov}
     cap_gnss_ptr->process();
 }
-std::shared_ptr<Subscriber> SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
+std::shared_ptr<WolfSubscriber> WolfSubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
 {
-    return std::make_shared<SubscriberGnssFix>(_sensor_ptr);
+    return std::make_shared<WolfSubscriberGnssFix>(_sensor_ptr);
 }