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

Every call to canTransform implementation throws Warning message print until transform is received. #358

Open
tgreier opened this issue Dec 15, 2020 · 6 comments · May be fixed by #491 or #556
Open
Assignees
Labels
enhancement New feature or request

Comments

@tgreier
Copy link

tgreier commented Dec 15, 2020

Can this be updated so that it only prints the Warning after the complete timeout expiration?

!canTransform(target_frame, source_frame, time) &&

@clalancette
Copy link
Contributor

Can you be more specific about which error message you are getting that you would like to be more quiet? (I think I know which one, but I want to be sure)

Changing the error message to only be printed after the timeout expiration would be a change to the semantics of lookupTransform. We can consider that, but we'd have to consider the implications of doing so.

If you really just want the print to be quieter, we could instead throttle how often the error message is printed without changing the semantics.

A PR to do either would be welcome.

@clalancette clalancette added the enhancement New feature or request label Dec 15, 2020
@tgreier
Copy link
Author

tgreier commented Dec 15, 2020

Thank you for the quick response!
It is this one:
[lift_tilt_node-24] Warning: Invalid frame ID "lift_pivot_base_left_link" passed to canTransform argument target_frame - frame does not exist
[lift_tilt_node-24] at line 133 in /home/moog/Workspaces/ros2-foxy/core/src/ros2/geometry2/tf2/src/buffer_core.cpp

Would validateFrameId somehow need to be updated to throttle?

CompactFrameID BufferCore::validateFrameId(const char* function_name_arg, const std::string& frame_id) const

@clalancette
Copy link
Contributor

Would validateFrameId somehow need to be updated to throttle?

Yeah, that's the kind of thing I'm thinking about. However, thinking about it further, this could get a little complicated. We want to throttle the printout so that it only prints for the same frame once a second (or whatever), but if a different frame fails to be validated, we want to print that right away. So we would need to remember which frames we printed out before, but also make sure that we don't "leak" memory for every single frame. It is doable, but tricky.

@tfoote Do you have any thoughts on what we might want to do here? The "simplest" solution is to make tf2_ros::Buffer::canTransform not return until the timeout, but that is a semantic change (both from ROS 1 and from earlier ROS 2 versions) and so I'm a little afraid to make it.

@tfoote
Copy link
Contributor

tfoote commented Feb 4, 2021

At this level there is no sense of time for which to "timeout" the API is designed to be as low overhead as possible. The best solution I see for this is to pass in an error string pointer that will then be filled by the lower level functions. It sends out the warnings because otherwise the error will never be debuggable.

In the loop you can then choose to use the error string or to ignore the error string.


diff --git a/tf2_ros/src/buffer.cpp b/tf2_ros/src/buffer.cpp
index de745a3..bef6466 100644
--- a/tf2_ros/src/buffer.cpp
+++ b/tf2_ros/src/buffer.cpp
@@ -148,12 +148,15 @@ Buffer::canTransform(
     return false;
   }
 
+  // String to accept error string from lower level calls but then ignore.
+  std::string suppressed_error_string;
+
   rclcpp::Duration rclcpp_timeout(to_rclcpp(timeout));
 
   // poll for transform if timeout is set
   rclcpp::Time start_time = clock_->now();
   while (clock_->now() < start_time + rclcpp_timeout &&
-    !canTransform(target_frame, source_frame, time) &&
+    !canTransform(target_frame, source_frame, time, &suppressed_error_string) &&
     (clock_->now() + rclcpp::Duration(3, 0) >= start_time) &&  // don't wait bag loop detected
     (rclcpp::ok()))  // Make sure we haven't been stopped (won't work for pytf)
   {

The problem with this is that it will then trigger all other error cases to generate error strings. The next escalation is to pass through another argument that suppresses the logging. One potential solution I could see would be to adjust this to be a debug level log. Unfortunately I don't think that console_bridge directly supports a THROTTLED version of the logging macros which would likely be the simplest solution to slow it down.

Hopefully this is only an issue at startup, but we do want to avoid spamming a lot at startup.

@tfoote tfoote removed their assignment Feb 4, 2021
@tfoote
Copy link
Contributor

tfoote commented Feb 4, 2021

Related: ros/geometry2#468

@clalancette clalancette self-assigned this Feb 18, 2021
@guru-florida
Copy link

I would be good with the simple case of switching it to a debug log.

The spamming of the log window is killing me! lol. ;) It fills my console buffer in seconds since a few nodes use this function. Sometimes it's because I am debugging a module that is delaying the TF publisher...and especially then I am trying to watch the log output for other stuff. I've found a work-around is to inverse-grep the log-spam.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
4 participants