Go to the documentation of this file.00001
00002 import rcommander.tool_utils as tu
00003 from PyQt4.QtGui import *
00004 from PyQt4.QtCore import *
00005
00006 import pr2_common_action_msgs.msg as ca
00007 import functools as ft
00008 import pr2_controllers_msgs.msg as pm
00009
00010
00011 class GripperTool(tu.ToolBase):
00012
00013 def __init__(self, rcommander):
00014 tu.ToolBase.__init__(self, rcommander, 'gripper', 'Gripper', GripperState)
00015
00016 def fill_property_box(self, pbox):
00017 formlayout = pbox.layout()
00018
00019 self.radio_boxes, self.radio_buttons = tu.make_radio_box(pbox, ['Left', 'Right'], 'gripper_arm')
00020
00021 self.gripper_box = tu.SliderBox(pbox, 0.01, 8.4, 0.02, .01, 'gripper', units='cm')
00022
00023 self.effort_box = tu.SliderBox(pbox, 50., 200., 0., 40., 'effort', units='')
00024
00025 formlayout.addRow('&Side', self.radio_boxes)
00026 formlayout.addRow('&Gripper Opening', self.gripper_box.container)
00027 formlayout.addRow('&Effort', self.effort_box.container)
00028 pbox.update()
00029
00030 def new_node(self, name=None):
00031 selected_arm = None
00032 for r in self.radio_buttons:
00033 if r.isChecked():
00034 selected_arm = str(r.text()).lower()
00035 if selected_arm == None:
00036 raise RuntimeError('No arm selected!')
00037
00038 gsize = self.gripper_box.value()
00039 effort = self.effort_box.value()
00040
00041 if name == None:
00042 nname = self.name + str(self.counter)
00043 else:
00044 nname = name
00045 return GripperState(nname, selected_arm, gsize, effort)
00046
00047 def set_node_properties(self, gripper_state):
00048 if gripper_state.arm == 'left':
00049 self.radio_buttons[0].setChecked(True)
00050 if gripper_state.arm == 'right':
00051 self.radio_buttons[1].setChecked(True)
00052
00053 self.gripper_box.set_value(gripper_state.gripper_size)
00054 self.effort_box.set_value(gripper_state.effort)
00055
00056 def reset(self):
00057 self.gripper_box.set_value(0.0)
00058 self.effort_box.set_value(50.)
00059 self.radio_buttons[0].setChecked(True)
00060
00061
00062 class GripperState(tu.SimpleStateBase):
00063
00064 def __init__(self, name, arm, gripper_size, effort):
00065 if arm == 'left':
00066 action = 'l_gripper_controller/gripper_action'
00067 elif arm == 'right':
00068 action = 'r_gripper_controller/gripper_action'
00069
00070 tu.SimpleStateBase.__init__(self, name, \
00071 action, pm.Pr2GripperCommandAction,
00072 goal_cb_str = 'ros_goal')
00073
00074 self.gripper_size = gripper_size
00075 self.effort = effort
00076 self.arm = arm
00077
00078 def ros_goal(self, userdata, default_goal):
00079
00080
00081
00082 return pm.Pr2GripperCommandGoal(pm.Pr2GripperCommand(position=self.gripper_size/100., max_effort=self.effort))
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092