Skip to content

Commit 5cbe439

Browse files
author
Rachel
committed
First pass, ran yapf
1 parent 66383d8 commit 5cbe439

File tree

8 files changed

+339
-308
lines changed

8 files changed

+339
-308
lines changed

Diff for: src/herbpy/barretthand.py

+41-35
Original file line numberDiff line numberDiff line change
@@ -28,16 +28,14 @@
2828
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
2929
# POSSIBILITY OF SUCH DAMAGE.
3030

31-
import numpy, openravepy, time
31+
import numpy, openravepy
3232
from prpy import util
3333
from prpy.base.endeffector import EndEffector
34-
from prpy.controllers import (
35-
PositionCommandController, TriggerController)
34+
from prpy.controllers import (PositionCommandController, TriggerController)
3635
from geometry_msgs.msg import WrenchStamped
3736

3837

3938
class BarrettHand(EndEffector):
40-
4139
def __init__(self, sim, manipulator, bhd_namespace, ft_sim=True):
4240
"""End-effector wrapper for the BarrettHand.
4341
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):
4745
reading breakaway status) are not supported on the BH-262.
4846
@param sim whether the hand is simulated
4947
@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
5150
@param ft_sim whether the force/torque sensor is simulated
5251
"""
5352
EndEffector.__init__(self, manipulator)
@@ -67,25 +66,24 @@ def __init__(self, sim, manipulator, bhd_namespace, ft_sim=True):
6766
manipulator.SetChuckingDirection(closing_direction)
6867

6968
robot = self.manipulator.GetRobot()
70-
env = robot.GetEnv()
7169

7270
# Controller setup
7371
self.bhd_namespace = bhd_namespace
7472
self.hand_side = bhd_namespace[1:] # TODO hand name hack
7573
if not sim:
76-
self.controller = PositionCommandController('', self.hand_side +
77-
'_hand_controller')
74+
self.controller = PositionCommandController(
75+
'', self.hand_side + '_hand_controller')
7876
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)
8483

8584
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)
8987

9088
# TODO tactile sensors
9189

@@ -100,8 +98,8 @@ def GetFingerIndices(self):
10098
These are returned in the order: [ finger 0, finger 1, and finger 2 ].
10199
@return DOF indices of the fingers
102100
"""
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]
105103

106104
def GetIndices(self):
107105
""" Gets the DOF indices of this hand.
@@ -126,7 +124,7 @@ def MoveHand(self, f1=None, f2=None, f3=None, spread=None, timeout=None):
126124
@param timeout blocking execution timeout, in seconds
127125
"""
128126
curr_pos = self.GetDOFValues()
129-
preshape = [None]*4
127+
preshape = [None] * 4
130128
# Set control command and
131129
# default any None's to the current DOF values.
132130
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):
135133
preshape[3] = spread if spread is not None else curr_pos[3]
136134

137135
self.controller.SetDesired(preshape)
138-
util.WaitForControllers([ self.controller ], timeout=timeout)
136+
util.WaitForControllers([self.controller], timeout=timeout)
139137

140138
def OpenHand(hand, spread=None, timeout=None):
141139
"""Open the hand with a fixed spread.
@@ -151,13 +149,15 @@ def OpenHand(hand, spread=None, timeout=None):
151149
robot = hand.manipulator.GetRobot()
152150
p = openravepy.KinBody.SaveParameters
153151

154-
with robot.CreateRobotStateSaver(p.ActiveDOF | p.ActiveManipulator):
152+
with robot.CreateRobotStateSaver(p.ActiveDOF |
153+
p.ActiveManipulator):
155154
hand.manipulator.SetActive()
156155
robot.task_manipulation.ReleaseFingers()
157156

158-
util.WaitForControllers([ hand.controller ], timeout=timeout)
157+
util.WaitForControllers([hand.controller], timeout=timeout)
159158
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)
161161

162162
def CloseHand(hand, spread=None, timeout=None):
163163
"""Close the hand with a fixed spread.
@@ -173,13 +173,15 @@ def CloseHand(hand, spread=None, timeout=None):
173173
robot = hand.manipulator.GetRobot()
174174
p = openravepy.KinBody.SaveParameters
175175

176-
with robot.CreateRobotStateSaver(p.ActiveDOF | p.ActiveManipulator):
176+
with robot.CreateRobotStateSaver(p.ActiveDOF |
177+
p.ActiveManipulator):
177178
hand.manipulator.SetActive()
178179
robot.task_manipulation.CloseFingers()
179180

180-
util.WaitForControllers([ hand.controller ], timeout=timeout)
181+
util.WaitForControllers([hand.controller], timeout=timeout)
181182
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)
183185

184186
def ResetHand(hand):
185187
"""Reset the hand.
@@ -188,7 +190,8 @@ def ResetHand(hand):
188190
clear the fingers' breakaway state. This function blocks until the
189191
reset is complete.
190192
"""
191-
raise NotImplementedError('ResetHand not yet implemented under ros_control.')
193+
raise NotImplementedError(
194+
'ResetHand not yet implemented under ros_control.')
192195

193196
def GetState(hand):
194197
"""Gets the current state of the hand
@@ -198,7 +201,8 @@ def GetState(hand):
198201
else:
199202
# TODO: We're missing documentation here. What is the "current
200203
# 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.")
202206

203207
def GetStrain(hand):
204208
""" Gets the most recent strain sensor readings.
@@ -207,7 +211,8 @@ def GetStrain(hand):
207211
if not hand.simulated:
208212
# This is because we are overriding the force/torque sensor datatype
209213
# 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")
211216
else:
212217
return numpy.zeros(3)
213218

@@ -216,10 +221,12 @@ def GetBreakaway(hand):
216221
@return a list of breakaway flags for each finger
217222
"""
218223
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.')
221228
else:
222-
return [ False, False, False ]
229+
return [False, False, False]
223230

224231
def GetForceTorque(hand):
225232
""" Gets the most recent force/torque sensor reading in the hand frame.
@@ -230,9 +237,8 @@ def GetForceTorque(hand):
230237
"""
231238
if not hand.ft_simulated:
232239
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)
236242
return sensor_data.wrench.force, sensor_data.wrench.torque
237243
else:
238244
return numpy.zeros(3), numpy.zeros(3)

Diff for: src/herbpy/herb.py

+20-13
Original file line numberDiff line numberDiff line change
@@ -4,22 +4,24 @@
44
import prpy.dependency_manager
55
from prpy.collision import (
66
BakedRobotCollisionCheckerFactory,
7-
SimpleRobotCollisionCheckerFactory,
8-
)
7+
SimpleRobotCollisionCheckerFactory, )
98
from openravepy import (
109
Environment,
1110
RaveCreateModule,
1211
RaveCreateCollisionChecker,
1312
RaveInitialize,
14-
openrave_exception,
15-
)
13+
openrave_exception, )
1614
from .herbbase import HerbBase
1715
from .herbrobot import HERBRobot
1816

1917
logger = logging.getLogger('herbpy')
2018

21-
def initialize(robot_xml=None, env_path=None, attach_viewer=False,
22-
sim=True, **kw_args):
19+
20+
def initialize(robot_xml=None,
21+
env_path=None,
22+
attach_viewer=False,
23+
sim=True,
24+
**kw_args):
2325
prpy.logger.initialize_logging()
2426

2527
# Hide TrajOpt logging.
@@ -53,7 +55,7 @@ def initialize(robot_xml=None, env_path=None, attach_viewer=False,
5355
robot = env.GetRobot(herb_name)
5456
if robot is None:
5557
raise ValueError('Unable to find robot with name "{:s}".'.format(
56-
herb_name))
58+
herb_name))
5759

5860
# Default to FCL.
5961
collision_checker = RaveCreateCollisionChecker(env, 'fcl')
@@ -81,15 +83,20 @@ def initialize(robot_xml=None, env_path=None, attach_viewer=False,
8183
' the slower SimpleRobotCollisionCheckerFactory.')
8284

8385
# Default arguments.
84-
keys = [ 'left_arm_sim', 'left_hand_sim', 'left_ft_sim',
85-
'right_arm_sim', 'right_hand_sim', 'right_ft_sim',
86-
'head_sim', 'talker_sim', 'segway_sim', 'perception_sim' ]
86+
keys = [
87+
'left_arm_sim', 'left_hand_sim', 'left_ft_sim', 'right_arm_sim',
88+
'right_hand_sim', 'right_ft_sim', 'head_sim', 'talker_sim',
89+
'segway_sim', 'perception_sim'
90+
]
8791
for key in keys:
8892
if key not in kw_args:
8993
kw_args[key] = sim
9094

91-
prpy.bind_subclass(robot, HERBRobot,
92-
robot_checker_factory=robot_checker_factory, **kw_args)
95+
prpy.bind_subclass(
96+
robot,
97+
HERBRobot,
98+
robot_checker_factory=robot_checker_factory,
99+
**kw_args)
93100

94101
if sim:
95102
dof_indices, dof_values \
@@ -112,7 +119,7 @@ def initialize(robot_xml=None, env_path=None, attach_viewer=False,
112119
env.SetViewer(attach_viewer)
113120
if env.GetViewer() is None:
114121
raise Exception('Failed creating viewer of type "{0:s}".'.format(
115-
attach_viewer))
122+
attach_viewer))
116123

117124
# Remove the ROS logging handler again. It might have been added when we
118125
# loaded or_rviz.

0 commit comments

Comments
 (0)