You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
this is a follow-up to #1855, because I think the fix there was incomplete.
When the parameter /rosout_disable_topics_generation is unset, the call to get_param_cached in https://github.com/ros/ros_comm/blob/noetic-devel/clients/rospy/src/rospy/impl/rosout.py#L91
returns the default value (False), but does not persist that default into the local param cache. Every subsequent call to rospy.loginfo/warn/error will then again query roscore the same way.
I tested this on the current ros noetic ubuntu packages as well as on the current ros_comm noetic-devel branch. When using rospy logging a lot, this can lead to roscore consuming high amounts of CPU time and becoming unresponsive to more useful requests (which is how we noticed the problem).
Steps to reproduce:
Launch three terminal windows:
In the first one, start roscore
In the second one, open the roscore logs: tail -f ~/.ros/log/latest/master.log
In the third one, run a python shell and execute this:
The second shell now prints this for each log call:
[rosmaster.master][INFO] 2023-07-12 18:54:16,598: +CACHEDPARAM [/rosout_disable_topics_generation] by /foo
[rosmaster.master][INFO] 2023-07-12 18:54:16,599: +CACHEDPARAM [/rosout_disable_topics_generation] by /foo
[rosmaster.master][INFO] 2023-07-12 18:54:16,600: +CACHEDPARAM [/rosout_disable_topics_generation] by /foo
[rosmaster.master][INFO] 2023-07-12 18:54:16,601: +CACHEDPARAM [/rosout_disable_topics_generation] by /foo
[rosmaster.master][INFO] 2023-07-12 18:54:16,603: +CACHEDPARAM [/rosout_disable_topics_generation] by /foo
If you open a fourth shell, and run rosparam set /rosout_disable_topics_generation False, and then execure the same python code again, no '+CACHEDPARAM' calls hit the roscore anymore.
I'm not sure what the correct behaviour would be here.
Maybe get_param_cached should set the default on roscore if the value is empty and a default has been provided
or, alternatively, it could cache "value does not exist on server" in some way, and subscribe to changes normally.
or, roscore could initialize /rosout_disable_topics_generation to False on startup (I'm unsure as to what that parameter actually does), which would fix the logging issue, but keep the unexpected non-caching behaviour for any other usage of get_param_cached.
The text was updated successfully, but these errors were encountered:
I should add that has a huge impact on the CPU utilization of rosmaster. On our system, setting this parameter (to either true or false, it doesn't matter which) halves the rosmaster CPU utilization.
Hi,
this is a follow-up to #1855, because I think the fix there was incomplete.
When the parameter
/rosout_disable_topics_generation
is unset, the call to get_param_cached inhttps://github.com/ros/ros_comm/blob/noetic-devel/clients/rospy/src/rospy/impl/rosout.py#L91
returns the default value (False), but does not persist that default into the local param cache. Every subsequent call to rospy.loginfo/warn/error will then again query roscore the same way.
I tested this on the current ros noetic ubuntu packages as well as on the current ros_comm noetic-devel branch. When using rospy logging a lot, this can lead to roscore consuming high amounts of CPU time and becoming unresponsive to more useful requests (which is how we noticed the problem).
Steps to reproduce:
Launch three terminal windows:
roscore
tail -f ~/.ros/log/latest/master.log
The second shell now prints this for each log call:
If you open a fourth shell, and run
rosparam set /rosout_disable_topics_generation False
, and then execure the same python code again, no '+CACHEDPARAM' calls hit the roscore anymore.I'm not sure what the correct behaviour would be here.
/rosout_disable_topics_generation
to False on startup (I'm unsure as to what that parameter actually does), which would fix the logging issue, but keep the unexpected non-caching behaviour for any other usage of get_param_cached.The text was updated successfully, but these errors were encountered: