Skip to content

Commit e22bf62

Browse files
committed
frame_manager: disable separate thread for tf listener to avoid tf race conditions during update cycle of all displays and cameras
During update cycle of displays and views (cameras) the tf buffer should not be updated. Otherwise it is possible that displays or cameras, which are updated at a later point in time within the cycle, use a more recent transform. This leads to undesired jittering of visuals. This affects displays, which use the latest available transform with ros::Time(). And all views/cameras as they always use the latest available transform.
1 parent ac6b080 commit e22bf62

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

src/rviz/frame_manager.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ FrameManager::FrameManager(std::shared_ptr<tf2_ros::Buffer> tf_buffer,
4747
tf_buffer ? std::move(tf_buffer) : std::make_shared<tf2_ros::Buffer>(ros::Duration(10 * 60));
4848
tf_listener_ = tf_listener ?
4949
std::move(tf_listener) :
50-
std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, ros::NodeHandle(), true);
50+
std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, ros::NodeHandle(), false);
5151

5252
setSyncMode(SyncOff);
5353
setPause(false);

0 commit comments

Comments
 (0)