diff --git a/config/params.yaml b/config/params.yaml
index 74babd7a565a406aa0ea19e6d7f741746623c921..abec6830a01b846f28f46769e3dae9cca5b97bc5 100644
--- a/config/params.yaml
+++ b/config/params.yaml
@@ -10,7 +10,7 @@ filter_coeff: 0.3
 speed_deadband: 0.1
 max_steer_angle: 0.5
 min_steer_angle: -0.5
-max_steer_control: 62.0
-min_steer_control: -77.0
+max_steer_control: 77.0
+min_steer_control: -62.0
 publish_tf: True
 
diff --git a/config/params_no_tf.yaml b/config/params_no_tf.yaml
index 6a370c1e76de7fd8da74bd7f1ab84fa2e94fdcaf..0a78dbe5df7e5dfffdcbb61405f249f19ccf4149 100644
--- a/config/params_no_tf.yaml
+++ b/config/params_no_tf.yaml
@@ -10,7 +10,7 @@ filter_coeff: 0.3
 speed_deadband: 0.1
 max_steer_angle: 0.5
 min_steer_angle: -0.5
-max_steer_control: 62.0
-min_steer_control: -77.0
+max_steer_control: 77.0
+min_steer_control: -62.0
 publish_tf: False
 
diff --git a/src/model_car_odometry_alg_node.cpp b/src/model_car_odometry_alg_node.cpp
index 1e41ee381cf4fda2f2d8c1dbd6b8388eee51d7e2..180151118dac7a3ddabd37721e903c906224eef0 100644
--- a/src/model_car_odometry_alg_node.cpp
+++ b/src/model_car_odometry_alg_node.cpp
@@ -69,7 +69,7 @@ void ModelCarOdometryAlgNode::mainNodeThread(void)
     else
     {
       this->odom_Odometry_msg_.header.frame_id=this->config_.odom_frame;
-      this->odom_Odometry_msg_.header.stamp=this->encoder_data.header.stamp;
+      this->odom_Odometry_msg_.header.stamp=ros::Time::now();
       this->odom_Odometry_msg_.child_frame_id=this->config_.robot_frame;
       // compute the increment of time
       dt=(this->odom_Odometry_msg_.header.stamp-last_time).toSec();
@@ -139,7 +139,7 @@ void ModelCarOdometryAlgNode::mainNodeThread(void)
 
         if(this->config_.publish_tf)
         {
-          this->transform_msg.header.stamp = this->encoder_data.header.stamp;
+          this->transform_msg.header.stamp = ros::Time::now();
           this->transform_msg.header.frame_id = this->config_.odom_frame;
           this->transform_msg.child_frame_id = this->config_.robot_frame;
           this->transform_msg.transform.translation.x = x;
@@ -149,7 +149,7 @@ void ModelCarOdometryAlgNode::mainNodeThread(void)
           this->tf2_broadcaster.sendTransform(this->transform_msg);
         }
         // publish ackermann specific data
-        this->ackermann_feedback_AckermannDriveStamped_msg_.header.stamp=this->encoder_data.header.stamp;
+        this->ackermann_feedback_AckermannDriveStamped_msg_.header.stamp=this->odom_Odometry_msg_.header.stamp;
         this->ackermann_feedback_AckermannDriveStamped_msg_.drive.speed=this->odom_Odometry_msg_.twist.twist.linear.x;
         this->ackermann_feedback_AckermannDriveStamped_msg_.drive.acceleration=0.0;
         this->ackermann_feedback_AckermannDriveStamped_msg_.drive.jerk=0.0;
@@ -159,7 +159,7 @@ void ModelCarOdometryAlgNode::mainNodeThread(void)
 
         last_steering_angle=this->steering_angle;
       }
-      last_time=this->encoder_data.header.stamp;
+      last_time=this->odom_Odometry_msg_.header.stamp;
     }
   }
   // [fill msg structures]