Fix initial position of sliders in joint_state_publisher GUI (#148)

Caused by a regression in 8c6cf9841c, 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.
This commit is contained in:
Timm Linder 2016-08-25 23:01:15 +02:00 committed by William Woodall
parent 05ea3f3beb
commit b87e6976df
1 changed files with 3 additions and 0 deletions

View File

@ -289,6 +289,9 @@ class JointStatePublisherGui(QWidget):
# Connect to the signal provided by QSignal # Connect to the signal provided by QSignal
slider.valueChanged.connect(self.onValueChanged) slider.valueChanged.connect(self.onValueChanged)
# Set zero positions read from parameters
self.center()
# Synchronize slider and displayed value # Synchronize slider and displayed value
self.sliderUpdate(None) self.sliderUpdate(None)