28
28
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29
29
# POSSIBILITY OF SUCH DAMAGE.
30
30
31
- import numpy , openravepy , time
31
+ import numpy , openravepy
32
32
from prpy import util
33
33
from prpy .base .endeffector import EndEffector
34
- from prpy .controllers import (
35
- PositionCommandController , TriggerController )
34
+ from prpy .controllers import (PositionCommandController , TriggerController )
36
35
from geometry_msgs .msg import WrenchStamped
37
36
38
37
39
38
class BarrettHand (EndEffector ):
40
-
41
39
def __init__ (self , sim , manipulator , bhd_namespace , ft_sim = True ):
42
40
"""End-effector wrapper for the BarrettHand.
43
41
This class wraps a BarrettHand end-effector that is controlled by BHD
@@ -47,7 +45,8 @@ def __init__(self, sim, manipulator, bhd_namespace, ft_sim=True):
47
45
reading breakaway status) are not supported on the BH-262.
48
46
@param sim whether the hand is simulated
49
47
@param manipulator manipulator the hand is attached to
50
- @param bhd_namespace ROS namespace that the BarrettHand driver is running in
48
+ @param bhd_namespace ROS namespace that the BarrettHand driver is
49
+ running in
51
50
@param ft_sim whether the force/torque sensor is simulated
52
51
"""
53
52
EndEffector .__init__ (self , manipulator )
@@ -67,25 +66,24 @@ def __init__(self, sim, manipulator, bhd_namespace, ft_sim=True):
67
66
manipulator .SetChuckingDirection (closing_direction )
68
67
69
68
robot = self .manipulator .GetRobot ()
70
- env = robot .GetEnv ()
71
69
72
70
# Controller setup
73
71
self .bhd_namespace = bhd_namespace
74
72
self .hand_side = bhd_namespace [1 :] # TODO hand name hack
75
73
if not sim :
76
- self .controller = PositionCommandController ('' , self . hand_side +
77
- '_hand_controller' )
74
+ self .controller = PositionCommandController (
75
+ '' , self . hand_side + '_hand_controller' )
78
76
else :
79
- self .controller = robot .AttachController (name = self .GetName (),
80
- args = 'IdealController' ,
81
- dof_indices = self .GetIndices (),
82
- affine_dofs = 0 ,
83
- simulated = sim )
77
+ self .controller = robot .AttachController (
78
+ name = self .GetName (),
79
+ args = 'IdealController' ,
80
+ dof_indices = self .GetIndices (),
81
+ affine_dofs = 0 ,
82
+ simulated = sim )
84
83
85
84
self .ft_simulated = ft_sim
86
- self .ft_tare_controller = TriggerController ('' , self .hand_side +
87
- '_tare_controller' ,
88
- ft_sim )
85
+ self .ft_tare_controller = TriggerController (
86
+ '' , self .hand_side + '_tare_controller' , ft_sim )
89
87
90
88
# TODO tactile sensors
91
89
@@ -100,8 +98,8 @@ def GetFingerIndices(self):
100
98
These are returned in the order: [ finger 0, finger 1, and finger 2 ].
101
99
@return DOF indices of the fingers
102
100
"""
103
- names = [ 'j01' , 'j11' , 'j21' ]
104
- return [ self ._GetJointFromName (name ).GetDOFIndex () for name in names ]
101
+ names = ['j01' , 'j11' , 'j21' ]
102
+ return [self ._GetJointFromName (name ).GetDOFIndex () for name in names ]
105
103
106
104
def GetIndices (self ):
107
105
""" Gets the DOF indices of this hand.
@@ -126,7 +124,7 @@ def MoveHand(self, f1=None, f2=None, f3=None, spread=None, timeout=None):
126
124
@param timeout blocking execution timeout, in seconds
127
125
"""
128
126
curr_pos = self .GetDOFValues ()
129
- preshape = [None ]* 4
127
+ preshape = [None ] * 4
130
128
# Set control command and
131
129
# default any None's to the current DOF values.
132
130
preshape [0 ] = f1 if f1 is not None else curr_pos [0 ]
@@ -135,7 +133,7 @@ def MoveHand(self, f1=None, f2=None, f3=None, spread=None, timeout=None):
135
133
preshape [3 ] = spread if spread is not None else curr_pos [3 ]
136
134
137
135
self .controller .SetDesired (preshape )
138
- util .WaitForControllers ([ self .controller ], timeout = timeout )
136
+ util .WaitForControllers ([self .controller ], timeout = timeout )
139
137
140
138
def OpenHand (hand , spread = None , timeout = None ):
141
139
"""Open the hand with a fixed spread.
@@ -151,13 +149,15 @@ def OpenHand(hand, spread=None, timeout=None):
151
149
robot = hand .manipulator .GetRobot ()
152
150
p = openravepy .KinBody .SaveParameters
153
151
154
- with robot .CreateRobotStateSaver (p .ActiveDOF | p .ActiveManipulator ):
152
+ with robot .CreateRobotStateSaver (p .ActiveDOF |
153
+ p .ActiveManipulator ):
155
154
hand .manipulator .SetActive ()
156
155
robot .task_manipulation .ReleaseFingers ()
157
156
158
- util .WaitForControllers ([ hand .controller ], timeout = timeout )
157
+ util .WaitForControllers ([hand .controller ], timeout = timeout )
159
158
else :
160
- hand .MoveHand (f1 = 0.0 , f2 = 0.0 , f3 = 0.0 , spread = spread , timeout = timeout )
159
+ hand .MoveHand (
160
+ f1 = 0.0 , f2 = 0.0 , f3 = 0.0 , spread = spread , timeout = timeout )
161
161
162
162
def CloseHand (hand , spread = None , timeout = None ):
163
163
"""Close the hand with a fixed spread.
@@ -173,13 +173,15 @@ def CloseHand(hand, spread=None, timeout=None):
173
173
robot = hand .manipulator .GetRobot ()
174
174
p = openravepy .KinBody .SaveParameters
175
175
176
- with robot .CreateRobotStateSaver (p .ActiveDOF | p .ActiveManipulator ):
176
+ with robot .CreateRobotStateSaver (p .ActiveDOF |
177
+ p .ActiveManipulator ):
177
178
hand .manipulator .SetActive ()
178
179
robot .task_manipulation .CloseFingers ()
179
180
180
- util .WaitForControllers ([ hand .controller ], timeout = timeout )
181
+ util .WaitForControllers ([hand .controller ], timeout = timeout )
181
182
else :
182
- hand .MoveHand (f1 = 3.2 , f2 = 3.2 , f3 = 3.2 , spread = spread , timeout = timeout )
183
+ hand .MoveHand (
184
+ f1 = 3.2 , f2 = 3.2 , f3 = 3.2 , spread = spread , timeout = timeout )
183
185
184
186
def ResetHand (hand ):
185
187
"""Reset the hand.
@@ -188,7 +190,8 @@ def ResetHand(hand):
188
190
clear the fingers' breakaway state. This function blocks until the
189
191
reset is complete.
190
192
"""
191
- raise NotImplementedError ('ResetHand not yet implemented under ros_control.' )
193
+ raise NotImplementedError (
194
+ 'ResetHand not yet implemented under ros_control.' )
192
195
193
196
def GetState (hand ):
194
197
"""Gets the current state of the hand
@@ -198,7 +201,8 @@ def GetState(hand):
198
201
else :
199
202
# TODO: We're missing documentation here. What is the "current
200
203
# state" of the hand? How do we interpret the return value?
201
- raise NotImplementedError ("Hand.GetState() not yet implemented under ros_control." )
204
+ raise NotImplementedError (
205
+ "Hand.GetState() not yet implemented under ros_control." )
202
206
203
207
def GetStrain (hand ):
204
208
""" Gets the most recent strain sensor readings.
@@ -207,7 +211,8 @@ def GetStrain(hand):
207
211
if not hand .simulated :
208
212
# This is because we are overriding the force/torque sensor datatype
209
213
# sensor_data = hand.handstate_sensor.GetSensorData()
210
- raise NotImplementedError ("Strain gauge not yet implemented in Python under ros_control" )
214
+ raise NotImplementedError (
215
+ "Strain gauge not yet implemented in Python under ros_control" )
211
216
else :
212
217
return numpy .zeros (3 )
213
218
@@ -216,10 +221,12 @@ def GetBreakaway(hand):
216
221
@return a list of breakaway flags for each finger
217
222
"""
218
223
if not hand .simulated :
219
- # This is because we are overriding the force/torque sensor datatype.
220
- raise NotImplementedError ('GetBreakaway not yet implemented under ros_control.' )
224
+ # This is because we are overriding the force/torque sensor
225
+ # datatype.
226
+ raise NotImplementedError (
227
+ 'GetBreakaway not yet implemented under ros_control.' )
221
228
else :
222
- return [ False , False , False ]
229
+ return [False , False , False ]
223
230
224
231
def GetForceTorque (hand ):
225
232
""" Gets the most recent force/torque sensor reading in the hand frame.
@@ -230,9 +237,8 @@ def GetForceTorque(hand):
230
237
"""
231
238
if not hand .ft_simulated :
232
239
import rospy
233
- sensor_data = rospy .wait_for_message (hand .bhd_namespace +
234
- '/ft_wrench' ,
235
- WrenchStamped )
240
+ sensor_data = rospy .wait_for_message (
241
+ hand .bhd_namespace + '/ft_wrench' , WrenchStamped )
236
242
return sensor_data .wrench .force , sensor_data .wrench .torque
237
243
else :
238
244
return numpy .zeros (3 ), numpy .zeros (3 )
0 commit comments