-
Notifications
You must be signed in to change notification settings - Fork 426
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
Logger::set_level does not lock the logging mutex #2120
Comments
In short: probably, yes. The longer answer is that I think there are two different problems in this area of code:
These uses are all for logging stuff, true, but it seems like they span both regular logging and the rosout logging. It's not totally clear to me what the design here should be, but I do think it needs a bit of work. Just my 2 cents. |
Well, from an rclcpp point of view, you cannot think of console logging, rosout logging and external library logging as separate things, as they are called consecutively on each log call, and multiple log calls can be made concurrently from different threads. Any writing call to logging is locked:
So currently any write access to any logging is mutually excluded by a mutex lock, except for the Logger::set_level. Hence this issue. Though, now that I am writing this, I just realized the following: Read access of the loglevel, through If this also needs a lock, then I think:
EDIT: this would not work as it locks both the read and the write part of the macro call. It is possible to split up at the rclcpp macro level, but the best solution is indeed as mentioned in ros2/rcutils#397. Currently there only is a mutex in the external log library, not in rcutils and rosout. |
The same issue as rcutils #393 I suppose.
Though that would mean that a log macro call from a low priority thread could block a call from a higher priority thread, even when disabled through the loglevel. |
I realized that I concluded basically what is already written in ros2/rcutils#397. |
Correct. Up until now, the design philosophy has always been to have the locking in the user-facing client libraries (rclcpp, rclpy, etc). This was both a decision to keep the lower layers simpler, as well as to make it easier to implement (as both C++ and Python have cross-platform locking solutions). However, because of the dependency-injection style of design here at the logging layer, it doesn't really work for logging. We really do need to solve ros2/rcutils#397 . |
Actually, could this be an alternative solution at the rclcpp level? If I understand it correctly the two main needs for ros2/rcutils#397 are: 1 ) An optimization:
2 ) Ensure that
So what if:
|
This situation is more common than you might think. In particular, when a user creates an action server, for instance, we create children named loggers for some of the internal things. Separately, if we are going to do this work for rclcpp, we'll also need to do the same for rclpy for the same reasons. All of that said, I do think that this is an easier and more viable way forward than trying to change rcutils. It improves the situation (and performance) for many common cases, and makes us thread-safe where we currently aren't. So with that said, @jrutgeer are you up for trying an implementation? I'm happy to do a review. |
I am not sure. I had checked that, and unless I am missing something, these are all node loggers, not named loggers.
Not sure yet, it is hard for me to assess how long it would take me. I haven't written any code since 2006. :-) Also I'm not sure yet about the best solution: A readers-writer lock isn't ideal, because this still blocks on the reader side if it concurs with a write. Ideally it should be possible to use logging macros in realtime code during testing, and disable them through the loglevel for normal use. But that implies a non-blocking read of the loglevel. So what about following alternative:
A further optimization for node loggers could be not to call
Also in the case of multiple nodes with the same name it would only work for the node that executes the service call. |
According to this, They propose the use of a spinlock intead of a mutex. |
Shouldn't
set_level()
also lock the global logging mutex?rclcpp/rclcpp/src/rclcpp/logger.cpp
Lines 111 to 115 in dbe555a
Since it writes to the rcutils hashmap, which has no locks (see also ros2/rcutils#397).
See also
get_child()
which does lock:rclcpp/rclcpp/src/rclcpp/logger.cpp
Lines 71 to 82 in dbe555a
The text was updated successfully, but these errors were encountered: