diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6debe122bdb4e0cd66b8234cb14098aed4a82c23..559f58c533f9c65a54694ca890b98deb5cb2eee8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -137,8 +137,8 @@ include_directories(
 # add_library(${PROJECT_NAME}
 #   src/${PROJECT_NAME}/wolf_ros.cpp
 # )
-add_library(wolf_subscriber_laser2D src/wolf_ros_subscriber_laser2D.cpp)
-add_library(wolf_ros_scan_visualizer src/wolf_ros_scan_visualizer.cpp)
+add_library(wolf_subscriber_laser2D src/wolf_subscriber_laser2D.cpp)
+add_library(wolf_scan_visualizer src/wolf_scan_visualizer.cpp)
 add_library(wolf_pointcloud_publisher src/wolf_pointcloud_publisher.cpp)
 
 ## Add cmake target dependencies of the library
@@ -168,11 +168,12 @@ target_link_libraries(wolf_subscriber_laser2D
             ${wolflaser_LIBRARIES}
             )
 Message("wolfroslibraries: ${wolf_ros_LIBRARIES}")
-target_link_libraries(wolf_ros_scan_visualizer
+target_link_libraries(wolf_scan_visualizer
             ${wolf_LIBRARIES}
             ${wolflaser_LIBRARIES}
             ${catkin_LIBRARIES}
-            /home/jvallve/code/iri_ws/devel/lib/libwolf_ros_visualizer.so
+            # /home/jvallve/code/iri_ws/devel/lib/libwolf_ros_visualizer.so
+            /home/jcasals/catkin_ws/devel/lib/libwolf_visualizer.so
             )
 target_link_libraries(wolf_pointcloud_publisher
             ${wolf_LIBRARIES}
diff --git a/include/wolf_pointcloud_publisher.h b/include/wolf_pointcloud_publisher.h
index ce95c7f5469d8805353c9118f39835948c81539b..84c45d1f315737d095a192b65fbbbd55bd127a22 100644
--- a/include/wolf_pointcloud_publisher.h
+++ b/include/wolf_pointcloud_publisher.h
@@ -6,7 +6,7 @@
 #include <core/common/wolf.h>
 #include <core/problem/problem.h>
 
-#include "wolf_ros_publisher.h"
+#include "wolf_publisher.h"
 #include "publisher_factory.h"
 
 /**************************
@@ -18,7 +18,7 @@
 
 using namespace wolf;
 
-class WolfPointcloudPublisher: public WolfRosPublisher
+class WolfPointcloudPublisher: public WolfPublisher
 {
     int max_frames_;
 public:
@@ -29,6 +29,6 @@ public:
     pcl::PointCloud<pcl::PointXYZRGB> buildPointCloudWithMeasurements(const ProblemPtr);
     void publishPointCloud(const ProblemPtr);
     void publish(const ProblemPtr problem) override;
-    static std::shared_ptr<WolfRosPublisher> create();
+    static std::shared_ptr<WolfPublisher> create();
 };
 #endif
diff --git a/include/wolf_ros_scan_visualizer.h b/include/wolf_scan_visualizer.h
similarity index 76%
rename from include/wolf_ros_scan_visualizer.h
rename to include/wolf_scan_visualizer.h
index 4476c84f9a98e3d5bea37326121b6d649519ea0a..33e0c936e4c20cef476599814683e9003a84d9cc 100644
--- a/include/wolf_ros_scan_visualizer.h
+++ b/include/wolf_scan_visualizer.h
@@ -1,5 +1,5 @@
-#ifndef WOLF_ROS_SCAN_VISUALIZER_H
-#define WOLF_ROS_SCAN_VISUALIZER_H
+#ifndef WOLF_SCAN_VISUALIZER_H
+#define WOLF_SCAN_VISUALIZER_H
 /**************************
  *      ROS includes      *
  **************************/
@@ -11,7 +11,7 @@
 #include <core/common/wolf.h>
 #include <core/problem/problem.h>
 
-#include <wolf_ros_visualizer.h>
+#include <wolf_visualizer.h>
 #include <visualizer_factory.h>
 
 /**************************
@@ -23,17 +23,17 @@
 
 using namespace wolf;
 
-class WolfRosScanVisualizer: public WolfRosVisualizer
+class WolfScanVisualizer: public WolfVisualizer
 {
     int max_frames_;
 public:
-    WolfRosScanVisualizer();
-    virtual ~WolfRosScanVisualizer(){};
+    WolfScanVisualizer();
+    virtual ~WolfScanVisualizer(){};
     void initialize(ros::NodeHandle &nh) override;
     void visualize(const ProblemPtr problem) override;
     virtual void fillFactorMarker(FactorBaseConstPtr          fac,
                                   visualization_msgs::Marker& fac_marker,
                                   visualization_msgs::Marker& fac_text_marker) override;
-    static std::shared_ptr<WolfRosVisualizer> create();
+    static std::shared_ptr<WolfVisualizer> create();
 };
 #endif
diff --git a/include/wolf_ros_subscriber_laser2D.h b/include/wolf_subscriber_laser2D.h
similarity index 77%
rename from include/wolf_ros_subscriber_laser2D.h
rename to include/wolf_subscriber_laser2D.h
index e4272027406318cd9dc3599ea642cb73c8b02e7b..10fec1b79634d1471aaaaa8717000eeb1bc2a0db 100644
--- a/include/wolf_ros_subscriber_laser2D.h
+++ b/include/wolf_subscriber_laser2D.h
@@ -32,26 +32,26 @@
 #include <iomanip>
 #include <queue>
 
-#include "wolf_ros_subscriber.h"
+#include "wolf_subscriber.h"
 #include "subscriber_factory.h"
 
 namespace wolf
 {
-class SubscriberWrapperLaser2D : public SubscriberWrapper
+class SubscriberLaser2D : public WolfSubscriber
 {
     protected:
         bool laser_intrinsics_set_;
 
     public:
         // Constructor
-        SubscriberWrapperLaser2D(const SensorBasePtr& sensor_ptr);
+        SubscriberLaser2D(const SensorBasePtr& sensor_ptr);
 
         virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic);
 
         void callback(const sensor_msgs::LaserScan::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(SubscriberWrapperLaser2D)
-}
\ No newline at end of file
+WOLF_REGISTER_SUBSCRIBER(SubscriberLaser2D)
+}
diff --git a/src/wolf_pointcloud_publisher.cpp b/src/wolf_pointcloud_publisher.cpp
index 66879a6f326790f6c6cf84d7d22db01afdb8cf02..bbe76a77380d5fccd2dd0bea2b99a0ac10dd4869 100644
--- a/src/wolf_pointcloud_publisher.cpp
+++ b/src/wolf_pointcloud_publisher.cpp
@@ -26,7 +26,7 @@
 #include <laser_geometry/laser_geometry.h>
 
 WolfPointcloudPublisher::WolfPointcloudPublisher() :
-    WolfRosPublisher()
+    WolfPublisher()
 {
 }
 void WolfPointcloudPublisher::initialize(ros::NodeHandle& nh, const std::string& topic)
@@ -165,7 +165,7 @@ void WolfPointcloudPublisher::publishPointCloud(const ProblemPtr problem)
     this->publisher_.publish(msg);
 }
 
-std::shared_ptr<WolfRosPublisher> WolfPointcloudPublisher::create()
+std::shared_ptr<WolfPublisher> WolfPointcloudPublisher::create()
 {
     return std::make_shared<WolfPointcloudPublisher>();
 }
diff --git a/src/wolf_ros_scan_visualizer.cpp b/src/wolf_scan_visualizer.cpp
similarity index 82%
rename from src/wolf_ros_scan_visualizer.cpp
rename to src/wolf_scan_visualizer.cpp
index 1cafb8484ee99a4335535ec1b5f93937cd2c4e3e..0fe84da178b1189a5dec1ff5726a80a4415cc36f 100644
--- a/src/wolf_ros_scan_visualizer.cpp
+++ b/src/wolf_scan_visualizer.cpp
@@ -1,4 +1,4 @@
-#include "wolf_ros_scan_visualizer.h"
+#include "wolf_scan_visualizer.h"
 #include "Eigen/src/Geometry/AngleAxis.h"
 #include "Eigen/src/Geometry/Transform.h"
 #include "core/common/wolf.h"
@@ -25,24 +25,24 @@
  **************************/
 #include <laser_geometry/laser_geometry.h>
 
-WolfRosScanVisualizer::WolfRosScanVisualizer() : WolfRosVisualizer()
+WolfScanVisualizer::WolfScanVisualizer() : WolfVisualizer()
 {
 }
-void WolfRosScanVisualizer::initialize(ros::NodeHandle& nh)
+void WolfScanVisualizer::initialize(ros::NodeHandle& nh)
 {
-    WolfRosVisualizer::initialize(nh);
+    WolfVisualizer::initialize(nh);
 
     nh.param<int>("num_frames_visualize", max_frames_, 2);
 }
-void WolfRosScanVisualizer::visualize(const ProblemPtr _problem)
+void WolfScanVisualizer::visualize(const ProblemPtr _problem)
 {
-    WolfRosVisualizer::visualize(_problem);
+    WolfVisualizer::visualize(_problem);
 }
-void WolfRosScanVisualizer::fillFactorMarker(FactorBaseConstPtr          fac,
+void WolfScanVisualizer::fillFactorMarker(FactorBaseConstPtr          fac,
                                              visualization_msgs::Marker& fac_marker,
                                              visualization_msgs::Marker& fac_text_marker)
 {
-    WolfRosVisualizer::fillFactorMarker(fac, fac_marker, fac_text_marker);
+    WolfVisualizer::fillFactorMarker(fac, fac_marker, fac_text_marker);
     if (fac->getFeature()->getType() == "FeatureIcpAlign" and
         (fac->getType() == "FactorOdom2D" or fac->getType() == "FactorOdom2DCloseloop"))
     {
@@ -86,8 +86,8 @@ void WolfRosScanVisualizer::fillFactorMarker(FactorBaseConstPtr          fac,
         fac_text_marker.pose.position.z = fac_text_marker.pose.position.z + 0.25;
     }
 }
-std::shared_ptr<WolfRosVisualizer> WolfRosScanVisualizer::create()
+std::shared_ptr<WolfVisualizer> WolfScanVisualizer::create()
 {
-    return std::make_shared<WolfRosScanVisualizer>();
+    return std::make_shared<WolfScanVisualizer>();
 }
-WOLF_REGISTER_VISUALIZER(WolfRosScanVisualizer)
+WOLF_REGISTER_VISUALIZER(WolfScanVisualizer)
diff --git a/src/wolf_ros_subscriber_laser2D.cpp b/src/wolf_subscriber_laser2D.cpp
similarity index 84%
rename from src/wolf_ros_subscriber_laser2D.cpp
rename to src/wolf_subscriber_laser2D.cpp
index faa7432374325598cb4bf18463b19abad0db323e..c4958cc534051bcf13e7cf724c91f05be6f2063b 100644
--- a/src/wolf_ros_subscriber_laser2D.cpp
+++ b/src/wolf_subscriber_laser2D.cpp
@@ -1,21 +1,21 @@
-#include "wolf_ros_subscriber_laser2D.h"
+#include "wolf_subscriber_laser2D.h"
 #include <limits>
 
 namespace wolf
 {
 // Constructor
-SubscriberWrapperLaser2D::SubscriberWrapperLaser2D(const SensorBasePtr& sensor_ptr): SubscriberWrapper(sensor_ptr)
+SubscriberLaser2D::SubscriberLaser2D(const SensorBasePtr& sensor_ptr): WolfSubscriber(sensor_ptr)
 {
     laser_intrinsics_set_ = false;
 }
 
 
-void SubscriberWrapperLaser2D::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
+void SubscriberLaser2D::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_ = nh.subscribe(topic, 100, &SubscriberWrapperLaser2D::callback, this);
+    sub_ = nh.subscribe(topic, 100, &SubscriberLaser2D::callback, this);
 }
 
-void SubscriberWrapperLaser2D::callback(const sensor_msgs::LaserScan::ConstPtr& msg)
+void SubscriberLaser2D::callback(const sensor_msgs::LaserScan::ConstPtr& msg)
 {
 
     CaptureLaser2DPtr new_capture = std::make_shared<CaptureLaser2D>(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, msg->ranges);
@@ -86,8 +86,8 @@ void SubscriberWrapperLaser2D::callback(const sensor_msgs::LaserScan::ConstPtr&
     //     }
 }
 
-std::shared_ptr<SubscriberWrapper> SubscriberWrapperLaser2D::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
+std::shared_ptr<WolfSubscriber> SubscriberLaser2D::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
 {
-    return std::make_shared<SubscriberWrapperLaser2D>(_sensor_ptr);
+    return std::make_shared<SubscriberLaser2D>(_sensor_ptr);
 }
 }