diff --git a/humanoid_modules/src/head_tracking_module.cpp b/humanoid_modules/src/head_tracking_module.cpp
index ead6714b17ae6636244b8ba6a75816a30bf2387f..4fc5dfdeafb539b32a2ecba862cc84eadcac7448 100644
--- a/humanoid_modules/src/head_tracking_module.cpp
+++ b/humanoid_modules/src/head_tracking_module.cpp
@@ -32,8 +32,7 @@ CHeadTrackingModule::CHeadTrackingModule(const std::string &name) : CHumanoidMod
   this->head_target.velocities.resize(2);
   this->head_target.accelerations.resize(2);
   this->head_target.effort.resize(2);
-  this->head_target_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.head_target_rate_hz),&CHeadTrackingModule::head_target_pub,this);
-  this->head_target_timer.stop();
+  this->head_target_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.head_target_rate_hz),&CHeadTrackingModule::head_target_pub,this,false,false);
   /* assign check callback functions to the PID services */
   this->set_pan_pid_service.set_call_check_function(boost::bind(&CHeadTrackingModule::check_set_pid_service,this,_1));
   this->get_pan_pid_service.set_call_check_function(boost::bind(&CHeadTrackingModule::check_get_pid_service,this,_1));
diff --git a/humanoid_modules/src/walk_module.cpp b/humanoid_modules/src/walk_module.cpp
index 6e076365a954688c81c4dac1046137afcf9d58b6..90040a9e41829c5f2b40bddcd19498596cd27ade 100644
--- a/humanoid_modules/src/walk_module.cpp
+++ b/humanoid_modules/src/walk_module.cpp
@@ -17,8 +17,7 @@ CWalkModule::CWalkModule(const std::string &name) : CHumanoidModule(name,WALK_MO
   this->cmd_vel_msg.angular.z=0.0;
   /* initiqalize the command velocity publisher */
   this->cmd_vel_publisher=this->module_nh.advertise<geometry_msgs::Twist>("cmd_vel",1);
-  this->cmd_vel_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.cmd_vel_rate_hz),&CWalkModule::cmd_vel_pub,this);
-  this->cmd_vel_timer.stop();
+  this->cmd_vel_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.cmd_vel_rate_hz),&CWalkModule::cmd_vel_pub,this,false,false);
   /* joint states subscriber */
   this->joint_state_subscriber=this->module_nh.subscribe("joint_states",1,&CWalkModule::joint_state_callback,this);
   /* fallen state subscriber */