Skip to content
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

tf::MessageFilter: processing new messages gets very slow when non-transformable messages are buffered #131

Open
tobiasberling opened this issue Sep 26, 2016 · 1 comment

Comments

@tobiasberling
Copy link

I observed RViz getting slower over time when a certain Display is active. Running a profiler shows that ros::TimeBase<ros::Time, ros::Duration>::operator<= takes about 1/3 of the RViz's processing time (over 2 minutes).
It turns out that, in my case, there are published sensor messages before the first tf message. Therefore, on each new message, the MessageFilter tries to find a transform for its cached messages (which in our case will never be transformable ever). See testMessage() in message_filter.h:341. I believe, this search for a suitable transform takes up a lot of the time (considering that RViz uses a transform cache length of 10 minutes, frame_manager.cpp:44.) After 10 minutes, the messages get thrown out of the message cache and RViz is not that slow anymore. (https://github.com/ros/geometry/blob/indigo-devel/tf/include/tf/message_filter.h#L341)

I am unsure what a good solution for this would look like

  • Is this a misuse by RViz considering a 10 minute cache length?
  • Should there be a second cache time for messages vs. transforms?
  • Should BufferCore::canTransform be faster in realizing that the requested time is not in its cache (i.e., requestedTime < earliestKnownTime) . (Not sure about this one. I have not looked at the implementation)

I am happy for any suggestions and might be able to provide a pull request once a proper solution has been identified.

Here's the call stack:

| Function                                                                                                |  Incl   |  Self   | Location              |
|---------------------------------------------------------------------------------------------------------|---------|---------|-----------------------|
| QCoreApplication::exec                                                                                  | 32.290s |  7.420s | libQtCore.so.4        |
|   rviz::VisualizationManager::onUpdate                                                                  | 23.958s |      0s | librviz.so            |
|     ros::spinOnce                                                                                       | 22.941s |      0s | libroscpp.so          |
|       ros::CallbackQueue::callAvailable                                                                 | 22.941s |      0s | libroscpp.so          |
|         ros::CallbackQueue::callOneCB                                                                   | 22.941s |      0s | libroscpp.so          |
|           ros::SubscriptionQueue::call                                                                  | 18.071s |      0s | libroscpp.so          |
|             ros::SubscriptionCallbackHelperT<ros::MessageEvent<[...]>::call                             | 17.989s |      0s | libmy_rviz_plugins.so |
|               boost::function1<void, ros::MessageEvent<sensor_msgs::LaserScan[...]> const&>::operator() | 17.977s |      0s | libmy_rviz_plugins.so |
|                 message_filters::Signal1<sensor_msgs::LaserScan<std::allocator<void>>>::call            | 17.977s |      0s | libmy_rviz_plugins.so |
|                   message_filters::CallbackHelper1T[...]::call                                          | 17.977s |      0s | libmy_rviz_plugins.so |
|                     boost::function1<void, ros::MessageEvent<sensor_msgs::LaserScan[...]>::operator()   | 17.965s |      0s | libmy_rviz_plugins.so |
|                       tf::MessageFilter<sensor_msgs::LaserScan<std::allocator<void>>>::add              | 17.957s |      0s | libmy_rviz_plugins.so |
|                         tf::MessageFilter<sensor_msgs::LaserScan<std::allocator<void>>>::testMessages   | 15.261s |      0s | libmy_rviz_plugins.so |
|                           tf::MessageFilter<sensor_msgs::LaserScan<std::allocator<void>>>::testMessage  | 15.251s |  0.028s | libmy_rviz_plugins.so |
|                             tf::Transformer::canTransform                                               | 14.947s |  0.018s | libtf.so              |
|                               tf2::BufferCore::canTransform                                             | 14.861s |      0s | libtf2.so             |
|                                 tf2::BufferCore::canTransformNoLock                                     | 14.767s |  0.010s | libtf2.so             |
|                                   tf2::BufferCore::walkToTopParent<tf2::CanTransformAccum>              | 14.757s |  0.034s | libtf2.so             |
|                                     tf2::TimeCache::getParent                                           | 14.671s |  1.074s | libtf2.so             |
|                                       ros::TimeBase<ros::Time, ros::Duration>::operator<=               | 13.111s | 13.111s | librostime.so         |
|                                       createExtrapolationException3                                     | 0.414s  |  0.020s | libtf.so              |
@tfoote
Copy link
Member

tfoote commented Sep 26, 2016

Approximately how many messages do you think are queuing up before transforms become available?

canTransform is generally pretty fast. I'm surprised to see most of the time is in the time/duration operator<=

Also what plugin are you using to render? Looking at a few random plugins they create their own MessageFilter and can populate the queue size. And I notice that common queue sizes are below 10.

Odometry Plugin Filter declaration and initialization with queue size of 5

The PointCloud2 queue size appears to be adjustable here with a default of 10

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants