Skip to content

Commit

Permalink
Suppress spam from calling canTransform (#529)
Browse files Browse the repository at this point in the history
* suppress spam in canTransform

* Uncrustify

Signed-off-by: Gonzalo de Pedro <[email protected]>

* Suppress console spam in other calls to canTransform

The user has few options to workaround potential console spam from canTransform.
If we want, it would be better to update the API to optional return the error string.

Signed-off-by: Jacob Perron <[email protected]>

Signed-off-by: Gonzalo de Pedro <[email protected]>
Signed-off-by: Jacob Perron <[email protected]>
Co-authored-by: Grigoriy Lipenko <[email protected]>
Co-authored-by: Jacob Perron <[email protected]>
(cherry picked from commit 8c2aa5a)
  • Loading branch information
gonzodepedro authored and mergify[bot] committed Jul 24, 2023
1 parent 98b92f5 commit aeb2fa4
Showing 1 changed file with 12 additions and 4 deletions.
16 changes: 12 additions & 4 deletions tf2_ros/src/buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,9 @@ Buffer::lookupTransform(
const std::string & target_frame, const std::string & source_frame,
const tf2::TimePoint & lookup_time, const tf2::Duration timeout) const
{
canTransform(target_frame, source_frame, lookup_time, timeout);
// Pass error string to suppress console spam
std::string error;
canTransform(target_frame, source_frame, lookup_time, timeout, &error);
return lookupTransform(target_frame, source_frame, lookup_time);
}

Expand All @@ -114,7 +116,9 @@ Buffer::lookupTransform(
const std::string & source_frame, const tf2::TimePoint & source_time,
const std::string & fixed_frame, const tf2::Duration timeout) const
{
canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout);
// Pass error string to suppress console spam
std::string error;
canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout, &error);
return lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame);
}

Expand Down Expand Up @@ -146,7 +150,9 @@ Buffer::canTransform(
// 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,
tf2::Duration(std::chrono::nanoseconds::zero()), errstr) &&
(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)
{
Expand Down Expand Up @@ -174,7 +180,9 @@ Buffer::canTransform(
// poll for transform if timeout is set
rclcpp::Time start_time = clock_->now();
while (clock_->now() < start_time + rclcpp_timeout &&
!canTransform(target_frame, target_time, source_frame, source_time, fixed_frame) &&
!canTransform(
target_frame, target_time, source_frame, source_time, fixed_frame,
tf2::Duration(std::chrono::nanoseconds::zero()), errstr) &&
(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)
{
Expand Down

0 comments on commit aeb2fa4

Please sign in to comment.