Skip to content
Snippets Groups Projects
Commit ccc56ea3 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Solved a bug: the time stamp published was the one taken from the Arduinos...

Solved a bug: the time stamp published was the one taken from the Arduinos instead of the computer time. This caused some TF problems.
parent 76a0efd5
No related branches found
No related tags found
No related merge requests found
......@@ -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
......@@ -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
......@@ -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]
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment