diff --git a/humanoid_common/package.xml b/humanoid_common/package.xml
index e5ca806d5650e35e025a6876f8a819b8cbc8df5c..7c5140f989f2bed54f90a5e70fadd19bb5e46ae4 100755
--- a/humanoid_common/package.xml
+++ b/humanoid_common/package.xml
@@ -50,6 +50,7 @@
   <run_depend>qr_global_loc</run_depend>
   <run_depend>teleop</run_depend>
   <run_depend>humanoid_modules</run_depend>
+  <run_depend>joints_cart_client</run_depend>
 
   <!-- The export tag contains other, unspecified, tags -->
   <export>
diff --git a/humanoid_modules/src/joints_cart_module.cpp b/humanoid_modules/src/joints_cart_module.cpp
index eb4e0d9c229cacdebfd763ddfe4443d69f39f00d..d18fa24ff44cbf2b15deeac547d693eaa5fb29b3 100644
--- a/humanoid_modules/src/joints_cart_module.cpp
+++ b/humanoid_modules/src/joints_cart_module.cpp
@@ -184,17 +184,19 @@ void CJointsCartModule::initialize_get_ik_msg(void)
 
 void CJointsCartModule::initialize_action_msg(sensor_msgs::JointState &solution)
 {
-  std::vector<double> speeds;
   unsigned int i=0;
 
   this->joints_traj_msg.trajectory.joint_names=solution.name;
   this->joints_traj_msg.trajectory.points[0].positions=solution.position;
-  if(this->motion_time=-1.0)
-    this->joints_traj_msg.trajectory.points[0].velocities=std::vector<double>(this->joints_traj_msg.trajectory.joint_names.size(),this->config.default_speed);
+  this->joints_traj_msg.trajectory.points[0].velocities.resize(this->joints_traj_msg.trajectory.joint_names.size());
+  if(this->motion_time==-1.0)
+  { 
+    for(i=0;i<this->joints_traj_msg.trajectory.joint_names.size();i++)
+      this->joints_traj_msg.trajectory.points[0].velocities[i]=0.1;//this->config.default_speed;
+  }
   else
   {
-    this->joints_traj_msg.trajectory.points[0].velocities.resize(this->joints_traj_msg.trajectory.joint_names.size());
-    for(i=0;i<speeds.size();i++)
+    for(i=0;i<this->joints_traj_msg.trajectory.joint_names.size();i++)
       this->joints_traj_msg.trajectory.points[0].velocities[i]=this->joints_traj_msg.trajectory.points[0].positions[i]/this->motion_time;
   }
   this->joints_traj_msg.trajectory.points[0].accelerations=std::vector<double>(this->joints_traj_msg.trajectory.joint_names.size(),0.0);