ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
543 stars 417 forks source link

Make throttle log macros accept a rclcpp::Duration #1929

Open Aposhian opened 2 years ago

Aposhian commented 2 years ago

Feature request

Feature description

Currently RCLCPP_*_THROTTLE (and the RCUTILS_LOG_*_THROTTLE_NAMED which they cal) arbitrarily accept the duration as an integral value of milliseconds. This is highly confusing, especially since it is not documented anywhere but deep in the source, in RCUTILS_LOG_CONDITION_THROTTLE_BEFORE, where it calls:

static rcutils_duration_value_t __rcutils_logging_duration = RCUTILS_MS_TO_NS((rcutils_duration_value_t)duration); 

If it accepts a simple integral value, it at least should be in nanoseconds. Better yet, it would be nice to change the rclcpp side of the macro to accept an rclcpp::Duration, which would be very uniform, and then it can be converted to milliseconds to satisfy RCUTILS strange interface.

Implementation considerations

Being a macro, I'm not sure how to define this without breaking backward compatibility. However, that brings up the point: why do the rclcpp logging utils need to be macros? We could define a variadic function instead that wraps the RCUTILS C macros, right?

clalancette commented 2 years ago

arbitrarily accept the duration as an integral value of milliseconds. This is highly confusing, especially since it is not documented anywhere but deep in the source, in RCUTILS_LOG_CONDITION_THROTTLE_BEFORE, where it calls:

I mean, I agree it is arbitrary, but so is nanoseconds. And I'll argue that milliseconds is more user-friendly than nanoseconds is. The fact that it is not documented anywhere is definitely a problem that we should fix.

Better yet, it would be nice to change the rclcpp side of the macro to accept an rclcpp::Duration, which would be very uniform, and then it can be converted to milliseconds to satisfy RCUTILS strange interface.

I'd be for an additional API that accepts rclcpp::Duration, though we need to worry about backwards compatibility. In particular, we need to make sure we don't end up breaking all of the code that already uses these macros. As long as we can satisfy that, then I think adding the Duration would be a good thing.

We could define a variadic function instead that wraps the RCUTILS C macros, right?

Unfortunately, no. It needs to be a macro so that we can get the FUNCTION and LINE values properly (otherwise they'll just show the line number of the variadic function, which isn't helpful for debugging).

aprotyas commented 2 years ago

This is highly confusing, especially since it is not documented anywhere but deep in the source, in RCUTILS_LOG_CONDITION_THROTTLE_BEFORE

An intermediate step would be to clarify documentation in rcutils/logging.py#L59:

diff --git a/rcutils/logging.py b/rcutils/logging.py
index bead217..af8eefe 100644
--- a/rcutils/logging.py
+++ b/rcutils/logging.py
@@ -56,7 +56,7 @@ skipfirst_doc_lines = [
 throttle_params = OrderedDict((
     ('get_time_point_value', 'Function that returns rcutils_ret_t and expects a '
         'rcutils_time_point_value_t pointer.'),
-    ('duration', 'The duration of the throttle interval'),
+    ('duration', 'The duration of the throttle interval as an integral value in milliseconds.'),
 ))
 throttle_args = {
     'condition_before': 'RCUTILS_LOG_CONDITION_THROTTLE_BEFORE(get_time_point_value, duration)',
aprotyas commented 2 years ago

I looked into implementation details for a bit, and to keep compatibility I think some kind of compile-time check on the duration type is the way to go. Since rcutils is written in C, said approach is cumbersome to do, but the _Generic expression selection syntax looks reasonable. This approach doesn't compile but if anyone wants some inspiration for implementation, here you go.

Changes in rcutils/resource/logging_macros.h.em:

diff --git a/resource/logging_macros.h.em b/resource/logging_macros.h.em
index 7d72263..14fdb66 100644
--- a/resource/logging_macros.h.em
+++ b/resource/logging_macros.h.em
@@ -165,6 +165,16 @@ typedef bool (* RclLogFilter)();
 }
 ///@@}

+enum t_rcutils_duration_type
+{
+  integral_duration,
+  rclcpp_duration,
+};
+
+#define rcutils_duration_type(duration) _Generic( (duration), \
+    rcutils_duration_value_t: integral_duration, \
+    default: rclcpp_duration)
+
 /** @@name Macros for the `throttle` condition which ignores log calls if the
  * last logged message is not longer ago than the specified duration.
  */
@@ -174,7 +184,15 @@ typedef bool (* RclLogFilter)();
  * A macro initializing and checking the `throttle` condition.
  */
 #define RCUTILS_LOG_CONDITION_THROTTLE_BEFORE(get_time_point_value, duration) { \
-    static rcutils_duration_value_t __rcutils_logging_duration = RCUTILS_MS_TO_NS((rcutils_duration_value_t)duration); \
+    static rcutils_duration_value_t __rcutils_logging_duration; \
+    switch (rcutils_duration_type(duration)) { \
+      case integral_duration: \
+        __rcutils_logging_duration = RCUTILS_MS_TO_NS((rcutils_duration_value_t)duration); \
+        break; \
+      case rclcpp_duration: \
+        __rcutils_logging_duration = duration.nanoseconds(); \
+        break; \
+    } \
     static rcutils_time_point_value_t __rcutils_logging_last_logged = 0; \
     rcutils_time_point_value_t __rcutils_logging_now = 0; \
     bool __rcutils_logging_condition = true; \
danzimmerman commented 1 year ago

I think that this is an issue that

So until there's a solution here, I think this might this deserve a documentation sidebar on the ROS2 docs here:

https://docs.ros.org/en/rolling/Tutorials/Demos/Logging-and-logger-configuration.html#logging-throttled

I found myself in the code yet again looking at .nanoseconds() and .to_chrono() to log at some fraction of a loop rate.

I've got a draft docs PR up here:

https://github.com/ros2/ros2_documentation/pull/3143

fujitatomoya commented 1 year ago

IMO, milliseconds is not bad arguments.

https://github.com/ros2/rcutils/pull/359 has been merged, and documentation update makes sense to me.