diff --git a/src/ros_subscribe-python-module-py.cc b/src/ros_subscribe-python-module-py.cc
new file mode 100644
index 0000000000000000000000000000000000000000..cbe164e5b46937607d1787c6e60913f26cbadcdb
--- /dev/null
+++ b/src/ros_subscribe-python-module-py.cc
@@ -0,0 +1,17 @@
+#include <dynamic-graph/python/module.hh>
+#include "ros_subscribe.hh"
+
+namespace dg = dynamicgraph;
+
+
+BOOST_PYTHON_MODULE(wrap)
+{
+  bp::import("dynamic_graph");
+
+  dg::python::exposeEntity<dg::RosSubscribe, bp::bases<dg::Entity>, dg::python::AddCommands>()
+    .def("clear", &dg::RosSubscribe::clear, "Remove all signals reading data from a ROS topic")
+    .def("rm", &dg::RosSubscribe::rm, "Remove a signal reading data from a ROS topic",
+        bp::args("signal_name"))
+    .def("list", &dg::RosSubscribe::list, "List signals reading data from a ROS topic")
+    ;
+}
diff --git a/src/ros_subscribe-python.hh b/src/ros_subscribe-python.hh
deleted file mode 100644
index 4a0bb03afa8c34ef1bf178534179698ea40e91b7..0000000000000000000000000000000000000000
--- a/src/ros_subscribe-python.hh
+++ /dev/null
@@ -1,3 +0,0 @@
-#include "ros_subscribe.hh"
-
-typedef boost::mpl::vector< dynamicgraph::RosSubscribe > entities_t;
diff --git a/src/ros_subscribe.cpp b/src/ros_subscribe.cpp
index f046af6dc30e08bd90b341e81806f2ec19eded30..cfa01a201002db721842351a21227276b8404b27 100644
--- a/src/ros_subscribe.cpp
+++ b/src/ros_subscribe.cpp
@@ -18,24 +18,6 @@ DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosSubscribe, "RosSubscribe");
 
 namespace command {
 namespace rosSubscribe {
-Clear::Clear(RosSubscribe& entity, const std::string& docstring)
-    : Command(entity, std::vector<Value::Type>(), docstring) {}
-
-Value Clear::doExecute() {
-  RosSubscribe& entity = static_cast<RosSubscribe&>(owner());
-
-  entity.clear();
-  return Value();
-}
-
-List::List(RosSubscribe& entity, const std::string& docstring)
-    : Command(entity, std::vector<Value::Type>(), docstring) {}
-
-Value List::doExecute() {
-  RosSubscribe& entity = static_cast<RosSubscribe&>(owner());
-  return Value(entity.list());
-}
-
 Add::Add(RosSubscribe& entity, const std::string& docstring)
     : Command(entity, boost::assign::list_of(Value::STRING)(Value::STRING)(Value::STRING), docstring) {}
 
@@ -73,17 +55,6 @@ Value Add::doExecute() {
     throw std::runtime_error("bad type");
   return Value();
 }
-
-Rm::Rm(RosSubscribe& entity, const std::string& docstring)
-    : Command(entity, boost::assign::list_of(Value::STRING), docstring) {}
-
-Value Rm::doExecute() {
-  RosSubscribe& entity = static_cast<RosSubscribe&>(owner());
-  std::vector<Value> values = getParameterValues();
-  const std::string& signal = values[0].value();
-  entity.rm(signal);
-  return Value();
-}
 }  // namespace rosSubscribe
 }  // end of namespace command.
 
@@ -106,29 +77,6 @@ RosSubscribe::RosSubscribe(const std::string& n) : dynamicgraph::Entity(n), nh_(
       "    - topic:  the topic name in ROS.\n"
       "\n";
   addCommand("add", new command::rosSubscribe::Add(*this, docstring));
-  docstring =
-      "\n"
-      "  Remove a signal reading data from a ROS topic\n"
-      "\n"
-      "  Input:\n"
-      "    - name of the signal to remove (see method list for the list of "
-      "signals).\n"
-      "\n";
-  addCommand("rm", new command::rosSubscribe::Rm(*this, docstring));
-  docstring =
-      "\n"
-      "  Remove all signals reading data from a ROS topic\n"
-      "\n"
-      "  No input:\n"
-      "\n";
-  addCommand("clear", new command::rosSubscribe::Clear(*this, docstring));
-  docstring =
-      "\n"
-      "  List signals reading data from a ROS topic\n"
-      "\n"
-      "  No input:\n"
-      "\n";
-  addCommand("list", new command::rosSubscribe::List(*this, docstring));
 }
 
 RosSubscribe::~RosSubscribe() {}
@@ -147,13 +95,10 @@ void RosSubscribe::rm(const std::string& signal) {
   }
 }
 
-std::string RosSubscribe::list() {
-  std::string result("[");
-  for (std::map<std::string, bindedSignal_t>::const_iterator it = bindedSignal_.begin(); it != bindedSignal_.end();
-       it++) {
-    result += "'" + it->first + "',";
-  }
-  result += "]";
+std::vector<std::string> RosSubscribe::list() {
+  std::vector<std::string> result(bindedSignal_.size());
+  std::transform(bindedSignal_.begin(), bindedSignal_.end(),
+      result.begin(), [](const auto& pair) { return pair.first; });
   return result;
 }
 
diff --git a/src/ros_subscribe.hh b/src/ros_subscribe.hh
index c5fd7dbb976cbb7b1050fbe2e79174cb81f66618..1928e486bb4ec60793811b5228208b6d5be912bb 100644
--- a/src/ros_subscribe.hh
+++ b/src/ros_subscribe.hh
@@ -31,9 +31,6 @@ using ::dynamicgraph::command::Value;
   }
 
 ROS_SUBSCRIBE_MAKE_COMMAND(Add);
-ROS_SUBSCRIBE_MAKE_COMMAND(Clear);
-ROS_SUBSCRIBE_MAKE_COMMAND(List);
-ROS_SUBSCRIBE_MAKE_COMMAND(Rm);
 
 #undef ROS_SUBSCRIBE_MAKE_COMMAND
 
@@ -62,7 +59,7 @@ class RosSubscribe : public dynamicgraph::Entity {
 
   void add(const std::string& signal, const std::string& topic);
   void rm(const std::string& signal);
-  std::string list();
+  std::vector<std::string> list();
   void clear();
 
   template <typename T>