ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

ros2 throttle logs

asked 2020-05-14 12:59:00 -0600

Neil Johnson gravatar image

I am trying to use logging statements like the following:

RCLCPP_INFO_THROTTLE(...)

in my code (C++, ROS2 Eloquent). I am used to the ROS1 syntax in which you specify a duration (as a float or double) and the print statement gets printed every so often. I found the code documentation for these here:

http://docs.ros2.org/latest/api/rclcp...

Here's what I tried in my code:

RCLCPP_INFO_THROTTLE(this->get_logger(), this->get_clock(), std::chrono::seconds(10), "Print statement here");

I am not clear on what to pass in for the clock and duration arguments. Are these supposed to be std::chrono clock/duration or rcpcpp::clock? I'm finding the documentation of clocks in ROS2 in general to be confusing and haven't found a good tutorial. Any help would be appreciated (I'm going to do my own throttling for now because this is proving difficult).

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
4

answered 2020-05-15 09:27:26 -0600

Mbuijs gravatar image

updated 2020-05-15 10:09:19 -0600

I was struggling with exactly this also this morning and I found the following to work (assuming this is a rclcpp::Node):

auto& clk = *this->get_clock();
RCLCPP_INFO_THROTTLE(this->get_logger(),
                     clk,
                     5000,
                     "Hello world");

clock argument

The source of RCLCPP_INFO_THROTTLE: http://docs.ros2.org/eloquent/api/rcl...

You can see here that the clock argument is used in a lambda capture and then inside the lambda. Due to this, the macro evaluation will result in this->get_clock(), which is not valid. As a workaround, I store the actual Clock (not the Clock::SharedPtr) in the clk variable and pass that along.

duration argument

2 levels deeper you can find the usage of duration: http://docs.ros2.org/eloquent/api/rcu...

Here you can see that the duration is converted to the standard rcutils_duration_value_t using the macro RCUTILS_MS_TO_NS, which is a multiplication by 1000LL * 1000LL. So 5000 means 5000 milliseconds.

edit flag offensive delete link more

Comments

Thanks for getting back to me so quickly! Your recommendation works great. Is there a good place to add this documentation? We want to adopt ROS2, but there are a lot of convenience functions and capabilities that we were used to using in ROS1 that are a lot less convenient in ROS2 (ros::Time and throttling among them). If all users have to dig into the source code that deep to get things working, I think it's going to be pretty discouraging to new users (and old users who aren't ready to adopt the new ways of C++11/14, etc).

Neil Johnson gravatar image Neil Johnson  ( 2020-05-15 10:32:28 -0600 )edit

Not sure about where to add this in documentation.

Regarding the C++11/14 aspect: I would recommend anyone to jump to C++14 or even C++17 as soon as possible, as it brings a lot of new functionality that just works great out of the box. I find cppreference.com a great resource for making the step.

Mbuijs gravatar image Mbuijs  ( 2020-05-25 07:47:23 -0600 )edit
0

answered 2020-06-23 15:22:51 -0600

APettinger gravatar image

I found that the answer from Mbuijs works well, however the this->clock() call to the node is not const, and was causing problems inside a const method of my class derived from rclcpp Node.

The following creates a new rclcpp::Clock and passes that to the throttle macro, and can be used inside a const method

auto steady_clock = rclcpp::Clock();
RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), steady_clock, 1000, "Hello World!");
edit flag offensive delete link more

Comments

This will have very different behavior. Please also be careful about your terminology. That's not a steady_clock as defined here: https://design.ros2.org/articles/cloc...

That clock will also not get any updates from the node.

There's a const version of get_clock which will return you a ConstSharedPtr

tfoote gravatar image tfoote  ( 2020-06-23 15:42:29 -0600 )edit

Is there somewhere any clear explanation why ROS_INFO_THROTTLE used seconds and RCLCPP_INFO_THROTTLE uses milliseconds?

Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2020-10-03 18:46:18 -0600 )edit

This worked for me. Thanks.

basti.hunter gravatar image basti.hunter  ( 2022-02-25 03:23:17 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2020-05-14 12:59:00 -0600

Seen: 6,281 times

Last updated: Jun 23 '20