Mapviz slowdown/freeze because of GetTransform
I am having serious problems of usability due to the fact that the GUI freeze when I change the value of Fixed Frame.
Digging into the issue I noticed that it happens when the tf is not properly defined for one of the loaded plugins; apparently the entire slow-down problem comes from swri_transform_manager.
https://github.com/swri-robotics/marti_common/blob/master/swri_transform_util/src/transform_manager.cpp#L358
My first question is: does that wait really help user code? Shouldn't the client code decide if it wants to wait or not?
Secondary, can't we move this query to a thread different from the Qt main loop to keep the GUI responsive?
@evenator
Yes, this is an issue.
I think the best solution is to create a new version of the function with a timeout parameter:
bool TransformManager::GetTransform( const std::string& target_frame, const std::string& source_frame, const ros::Time& time, const ros::Duration& timeout, tf::StampedTransform& transform) const
The old function can be implemented by calling the new function with the 0.1 timeout to prevent breaking existing code that might depend on the timeout. Creating a new function instead of replacing the old one will also keep the API compatible with already compiled code.
I think it'd make sense to add a new function with a timeout, and then we should probably review all of the existing code in Mapviz that uses it and call it without a timeout (when appropriate).
I Agree.
I've added the proposed methods to swri_transform in swri-robotics/marti_common#498. Once that's merged, we can make the necessary changes to mapviz.
RViz doesn't use tf::TransformListener for this, they instead subscribe to topic through tf2_ros::MessageFilter
Yes this is indeed the common cause of the GUI freeze/stutter. It is much more noticeable when running ros over 4G network. Changing the timeout to 0.01 has made a significant improvement in the UI responsiveness, but of cause this is only a ugly and temporary workaround.
RViz doesn't use
tf::TransformListenerfor this, they instead subscribe to topic throughtf2_ros::MessageFilter
Line 26 in the linked cpp file invokes tf2_ros::Buffer::transform(), which is effectively a call to lookupTransform() plus some transformation calculation, so it is the same as how mapviz gets the transformation.