From b87e6976dfedf8e2f484ac47d0c6e86774648055 Mon Sep 17 00:00:00 2001 From: Timm Linder Date: Thu, 25 Aug 2016 23:01:15 +0200 Subject: [PATCH] Fix initial position of sliders in joint_state_publisher GUI (#148) Caused by a regression in 8c6cf9841cb, the slider positions are not initialized correctly from the provided zero positions at startup. This commit fixes the issue, by adding the call to center() again that got lost. --- .../joint_state_publisher/joint_state_publisher | 3 +++ 1 file changed, 3 insertions(+) diff --git a/joint_state_publisher/joint_state_publisher/joint_state_publisher b/joint_state_publisher/joint_state_publisher/joint_state_publisher index ef1ffec..18f991e 100755 --- a/joint_state_publisher/joint_state_publisher/joint_state_publisher +++ b/joint_state_publisher/joint_state_publisher/joint_state_publisher @@ -289,6 +289,9 @@ class JointStatePublisherGui(QWidget): # Connect to the signal provided by QSignal slider.valueChanged.connect(self.onValueChanged) + # Set zero positions read from parameters + self.center() + # Synchronize slider and displayed value self.sliderUpdate(None)