Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions robot_controllers/include/robot_controllers/diff_drive_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -183,6 +183,8 @@ class DiffDriveBaseController : public Controller

boost::shared_ptr<tf::TransformBroadcaster> broadcaster_;
bool publish_tf_;
// The time of the most recent published state
ros::Time last_published_tf_stamp_;

bool enabled_;
bool ready_;
Expand Down
6 changes: 5 additions & 1 deletion robot_controllers/src/diff_drive_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,7 +375,8 @@ void DiffDriveBaseController::publishCallback(const ros::TimerEvent& event)
msg.header.stamp = ros::Time::now();
odom_pub_.publish(msg);

if (publish_tf_)
// As of ROS Noetic, TF2 will issue warnings whenever we try to publish with the same time stamp.
if (publish_tf_ && msg.header.stamp > last_published_tf_stamp_)
{
tf::Transform transform;
transform.setOrigin(tf::Vector3(msg.pose.pose.position.x, msg.pose.pose.position.y, 0.0));
Expand All @@ -389,6 +390,9 @@ void DiffDriveBaseController::publishCallback(const ros::TimerEvent& event)
*/
broadcaster_->sendTransform(tf::StampedTransform(transform, msg.header.stamp, msg.header.frame_id, msg.child_frame_id));
}

// Retain the last published stamp for detecting repeatedtransforms in future cycles
last_published_tf_stamp_ = msg.header.stamp;
}

void DiffDriveBaseController::scanCallback(
Expand Down