Merge pull request #100 from ablasdel/indigo-devel
randomize button for jsp gui
This commit is contained in:
commit
15ac3e07ff
|
@ -1,6 +1,7 @@
|
||||||
#!/usr/bin/env python
|
#!/usr/bin/env python
|
||||||
|
|
||||||
import rospy
|
import rospy
|
||||||
|
import random
|
||||||
import wx
|
import wx
|
||||||
import wx.lib.newevent
|
import wx.lib.newevent
|
||||||
import xml.dom.minidom
|
import xml.dom.minidom
|
||||||
|
@ -267,12 +268,15 @@ class JointStatePublisherGui(wx.Frame):
|
||||||
self.Bind(self.EVT_UPDATESLIDERS, self.updateSliders)
|
self.Bind(self.EVT_UPDATESLIDERS, self.updateSliders)
|
||||||
|
|
||||||
### Buttons ###
|
### Buttons ###
|
||||||
self.ctrbutton = wx.Button(panel, 1, 'Center')
|
self.randbutton = wx.Button(panel, 1, 'Randomize')
|
||||||
|
self.ctrbutton = wx.Button(panel, 2, 'Center')
|
||||||
self.Bind(wx.EVT_SLIDER, self.sliderUpdate)
|
self.Bind(wx.EVT_SLIDER, self.sliderUpdate)
|
||||||
|
|
||||||
wx.EVT_BUTTON(self, 1, self.center_event)
|
wx.EVT_BUTTON(self, 1, self.randomize_event)
|
||||||
|
wx.EVT_BUTTON(self, 2, self.center_event)
|
||||||
|
|
||||||
box.Add(self.ctrbutton, 0, wx.EXPAND)
|
box.Add(self.randbutton, 0, wx.EXPAND)
|
||||||
|
box.Add(self.ctrbutton, 1, wx.EXPAND)
|
||||||
|
|
||||||
panel.SetSizer(box)
|
panel.SetSizer(box)
|
||||||
self.center()
|
self.center()
|
||||||
|
@ -309,6 +313,17 @@ class JointStatePublisherGui(wx.Frame):
|
||||||
joint_info['slidervalue'] = self.valueToSlider(joint['zero'], joint)
|
joint_info['slidervalue'] = self.valueToSlider(joint['zero'], joint)
|
||||||
self.update_values()
|
self.update_values()
|
||||||
|
|
||||||
|
def randomize_event(self, event):
|
||||||
|
self.randomize()
|
||||||
|
|
||||||
|
def randomize(self):
|
||||||
|
rospy.loginfo("Randomizing")
|
||||||
|
for (name,joint_info) in self.joint_map.items():
|
||||||
|
joint = joint_info['joint']
|
||||||
|
joint_info['slidervalue'] = self.valueToSlider(random.uniform(joint['min'], joint['max']), joint)
|
||||||
|
self.update_values()
|
||||||
|
|
||||||
|
|
||||||
def sliderUpdate(self, event):
|
def sliderUpdate(self, event):
|
||||||
for (name,joint_info) in self.joint_map.items():
|
for (name,joint_info) in self.joint_map.items():
|
||||||
joint_info['slidervalue'] = joint_info['slider'].GetValue()
|
joint_info['slidervalue'] = joint_info['slider'].GetValue()
|
||||||
|
|
Loading…
Reference in New Issue