diff --git a/src/ros_joint_state.cpp b/src/ros_joint_state.cpp
index 24b96e916a9cecaf616fc9144bd0da69beef5b10..dccc85ed93b645cd20d3bc00173ec69b2ea362f3 100644
--- a/src/ros_joint_state.cpp
+++ b/src/ros_joint_state.cpp
@@ -14,6 +14,7 @@
 namespace dynamicgraph
 {
   DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosJointState, "RosJointState");
+  const double RosJointState::ROS_JOINT_STATE_PUBLISHER_RATE = 0.01;
 
   namespace command
   {
diff --git a/src/ros_joint_state.hh b/src/ros_joint_state.hh
index 6ce379c2e3bb659971c255f1c5dbfaf74c26af13..cb2115724d4b4a61bfb848546dd89b4f345ee310 100644
--- a/src/ros_joint_state.hh
+++ b/src/ros_joint_state.hh
@@ -21,7 +21,7 @@ namespace dynamicgraph
     /// \brief Vector input signal.
     typedef SignalPtr<ml::Vector, int> signalVectorIn_t;
 
-    static const double ROS_JOINT_STATE_PUBLISHER_RATE = 1. / 100.;
+    static const double ROS_JOINT_STATE_PUBLISHER_RATE;
 
     RosJointState (const std::string& n);
     virtual ~RosJointState ();
diff --git a/src/ros_publish.cpp b/src/ros_publish.cpp
index c7bc2122d1bea94043a6042677917082c176d393..5ef54875e81c8365e1e8ba2336b2950102f000c6 100644
--- a/src/ros_publish.cpp
+++ b/src/ros_publish.cpp
@@ -20,6 +20,8 @@
 namespace dynamicgraph
 {
   DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosPublish, "RosPublish");
+ 
+  const double RosPublish::ROS_JOINT_STATE_PUBLISHER_RATE = 0.01;
 
   namespace command
   {
diff --git a/src/ros_publish.hh b/src/ros_publish.hh
index 03a564599f988c25ca29ca43b6feea125bb4ac32..3a6d5d426b1948ed2a8ec25c347dffba7cfa6526 100644
--- a/src/ros_publish.hh
+++ b/src/ros_publish.hh
@@ -60,7 +60,7 @@ namespace dynamicgraph
       callback_t>
     bindedSignal_t;
 
-    static const double ROS_JOINT_STATE_PUBLISHER_RATE = 1. / 100.;
+    static const double ROS_JOINT_STATE_PUBLISHER_RATE;
 
     RosPublish (const std::string& n);
     virtual ~RosPublish ();