Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

throttle TF_REPEATED_DATA to 10 seconds #516

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
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: 1 addition & 1 deletion tf2/include/tf2/time_cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class TimeCache : public TimeCacheInterface
L_TransformStorage storage_;

ros::Duration max_storage_time_;

ros::Time last_repeated_warn_time_;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This most probably wouldn't make it into Noetic. It changes the ABI of existing code, which would require a total rebuild of the whole Noetic buildfarm.

I suggest moving this completely to the .cpp . You can make this a static variable in the .cpp file, which would preserve ABI. It could also simplify the implementation.

If you no longer feel the urge to get this fix merged, ping @klaxalk , he told he could find some time to dedicate to this fix ;)


/// A helper function for getData
//Assumes storage is already locked for it
Expand Down
5 changes: 4 additions & 1 deletion tf2/src/buffer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,10 @@ bool BufferCore::setTransform(const geometry_msgs::TransformStamped& transform_i
}
else
{
CONSOLE_BRIDGE_logWarn((error_string+" for frame %s at time %lf according to authority %s").c_str(), stripped.child_frame_id.c_str(), stripped.header.stamp.toSec(), authority.c_str());
if (error_string.size())
{
CONSOLE_BRIDGE_logWarn((error_string+" for frame %s at time %lf according to authority %s").c_str(), stripped.child_frame_id.c_str(), stripped.header.stamp.toSec(), authority.c_str());
}
return false;
}
}
Expand Down
9 changes: 8 additions & 1 deletion tf2/src/cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,8 +275,13 @@ bool TimeCache::insertData(const TransformStorage& new_data, std::string* error_
}
if (storage_it != storage_.end() && storage_it->stamp_ == new_data.stamp_)
{
if (error_str)
// Throttle TF_REPEATED_DATA error message to 10 seconds.
// Console bridge does not have throttling, so implement throttling here.
// Because insertData may be called prior to ros::Time being initialized,
// use the stamp from the message as "now".
if (error_str && new_data.stamp_ > last_repeated_warn_time_ + ros::Duration(10.0))
{
last_repeated_warn_time_ = new_data.stamp_;
*error_str = "TF_REPEATED_DATA ignoring data with redundant timestamp";
}
return false;
Expand All @@ -292,6 +297,8 @@ bool TimeCache::insertData(const TransformStorage& new_data, std::string* error_

void TimeCache::clearList()
{
// Reset the TF_REPEATED_DATA error message throttle.
last_repeated_warn_time_ = ros::Time(0.0);
storage_.clear();
}

Expand Down