Skip to content

Commit f4bb808

Browse files
committed
Added PEP8 fixes and lint corrections for prpy.planning.
Fixes a number of small syntax errors and non-compliant formatting in the `prpy.planning` modules.
1 parent 1d77c53 commit f4bb808

File tree

3 files changed

+80
-74
lines changed

3 files changed

+80
-74
lines changed

src/prpy/planning/cbirrt.py

Lines changed: 47 additions & 42 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
# - Neither the name of Carnegie Mellon University nor the names of its
1616
# contributors may be used to endorse or promote products derived from this
1717
# software without specific prior written permission.
18-
#
18+
#
1919
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
2020
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
2121
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
@@ -28,11 +28,13 @@
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
31+
import numpy
32+
import openravepy
3233
from ..util import SetTrajectoryTags
3334
from base import (BasePlanner, PlanningError, UnsupportedPlanningError,
3435
PlanningMethod, Tags)
35-
import prpy.kin, prpy.tsr
36+
import prpy.kin
37+
import prpy.tsr
3638

3739

3840
class CBiRRTPlanner(BasePlanner):
@@ -112,21 +114,21 @@ def PlanToEndEffectorOffset(self, robot, direction, distance,
112114
H_world_ee = manip.GetEndEffectorTransform()
113115

114116
# 'object frame w' is at ee, z pointed along direction to move
115-
H_world_w = prpy.kin.H_from_op_diff(H_world_ee[0:3,3], direction)
117+
H_world_w = prpy.kin.H_from_op_diff(H_world_ee[0:3, 3], direction)
116118
H_w_ee = numpy.dot(prpy.kin.invert_H(H_world_w), H_world_ee)
117119

118120
# Serialize TSR string (goal)
119121
Hw_end = numpy.eye(4)
120-
Hw_end[2,3] = distance
121-
122-
goaltsr = prpy.tsr.tsr.TSR(T0_w = numpy.dot(H_world_w,Hw_end),
123-
Tw_e = H_w_ee,
124-
Bw = numpy.zeros((6,2)),
125-
manip = robot.GetActiveManipulatorIndex())
126-
goal_tsr_chain = prpy.tsr.tsr.TSRChain(sample_goal = True,
127-
TSRs = [goaltsr])
122+
Hw_end[2, 3] = distance
123+
124+
goaltsr = prpy.tsr.tsr.TSR(T0_w=numpy.dot(H_world_w, Hw_end),
125+
Tw_e=H_w_ee,
126+
Bw=numpy.zeros((6, 2)),
127+
manip=robot.GetActiveManipulatorIndex())
128+
goal_tsr_chain = prpy.tsr.tsr.TSRChain(sample_goal=True,
129+
TSRs=[goaltsr])
128130
# Serialize TSR string (whole-trajectory constraint)
129-
Bw = numpy.zeros((6,2))
131+
Bw = numpy.zeros((6, 2))
130132
epsilon = 0.001
131133
Bw = numpy.array([[-epsilon, epsilon],
132134
[-epsilon, epsilon],
@@ -135,15 +137,16 @@ def PlanToEndEffectorOffset(self, robot, direction, distance,
135137
[-epsilon, epsilon],
136138
[-epsilon, epsilon]])
137139

138-
trajtsr = prpy.tsr.tsr.TSR(T0_w = H_world_w,
139-
Tw_e = H_w_ee,
140-
Bw = Bw,
141-
manip = robot.GetActiveManipulatorIndex())
142-
traj_tsr_chain = prpy.tsr.tsr.TSRChain(constrain=True, TSRs=[trajtsr])
140+
traj_tsr = prpy.tsr.tsr.TSR(
141+
T0_w=H_world_w, Tw_e=H_w_ee, Bw=Bw,
142+
manip=robot.GetActiveManipulatorIndex())
143+
traj_tsr_chain = prpy.tsr.tsr.TSRChain(constrain=True,
144+
TSRs=[traj_tsr])
143145

144146
kw_args.setdefault('psample', 0.1)
145147

146-
return self.Plan(robot,
148+
return self.Plan(
149+
robot,
147150
tsr_chains=[goal_tsr_chain, traj_tsr_chain],
148151
# Smooth since this is a constrained trajectory.
149152
smoothingitrs=smoothingitrs,
@@ -162,7 +165,6 @@ def PlanToTSR(self, robot, tsr_chains, smoothingitrs=100, **kw_args):
162165
@param smoothingitrs number of smoothing iterations to run
163166
@return traj output path
164167
"""
165-
psample = None
166168
is_constrained = False
167169

168170
for chain in tsr_chains:
@@ -176,7 +178,8 @@ def PlanToTSR(self, robot, tsr_chains, smoothingitrs=100, **kw_args):
176178
if not is_constrained:
177179
smoothingitrs = 0
178180

179-
return self.Plan(robot,
181+
return self.Plan(
182+
robot,
180183
smoothingitrs=smoothingitrs,
181184
tsr_chains=tsr_chains,
182185
**kw_args
@@ -187,41 +190,42 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
187190
extra_args=None, **kw_args):
188191
from openravepy import CollisionOptions, CollisionOptionsStateSaver
189192

190-
# TODO We may need this work-around because CBiRRT doesn't like it when
191-
# an IK solver other than GeneralIK is loaded (e.g. nlopt_ik).
192-
#self.ClearIkSolver(robot.GetActiveManipulator())
193+
# TODO We may need this work-around because CBiRRT doesn't like it
194+
# when an IK solver other than GeneralIK is loaded (e.g. nlopt_ik).
195+
# self.ClearIkSolver(robot.GetActiveManipulator())
193196

194197
self.env.LoadProblem(self.problem, robot.GetName())
195198

196-
args = [ 'RunCBiRRT' ]
199+
args = ['RunCBiRRT']
197200

198201
if extra_args is not None:
199202
args += extra_args
200203

201204
if smoothingitrs is not None:
202205
if smoothingitrs < 0:
203-
raise ValueError('Invalid number of smoothing iterations. Value'
204-
'must be non-negative; got {:d}.'.format(
205-
smoothingitrs))
206+
raise ValueError('Invalid number of smoothing iterations. '
207+
'Value must be non-negative; got {:d}.'
208+
.format(smoothingitrs))
206209

207-
args += [ 'smoothingitrs', str(smoothingitrs) ]
210+
args += ['smoothingitrs', str(smoothingitrs)]
208211

209212
if timelimit is not None:
210213
if not (timelimit > 0):
211214
raise ValueError('Invalid value for "timelimit". Limit must be'
212215
' non-negative; got {:f}.'.format(timelimit))
213216

214-
args += [ 'timelimit', str(timelimit) ]
217+
args += ['timelimit', str(timelimit)]
215218

216219
if allowlimadj is not None:
217-
args += [ 'allowlimadj', str(int(allowlimadj)) ]
220+
args += ['allowlimadj', str(int(allowlimadj))]
218221

219222
if psample is not None:
220223
if not (0 <= psample <= 1):
221-
raise ValueError('Invalid value for "psample". Value must be in'
222-
' the range [0, 1]; got {:f}.'.format(psample))
224+
raise ValueError('Invalid value for "psample". Value must be '
225+
'in the range [0, 1]; got {:f}.'
226+
.format(psample))
223227

224-
args += [ 'psample', str(psample) ]
228+
args += ['psample', str(psample)]
225229

226230
if jointstarts is not None:
227231
for start_config in jointstarts:
@@ -233,7 +237,8 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
233237
)
234238
)
235239

236-
args += ['jointstarts'] + self.serialize_dof_values(start_config)
240+
args += (['jointstarts'] +
241+
self.serialize_dof_values(start_config))
237242

238243
if jointgoals is not None:
239244
for goal_config in jointgoals:
@@ -254,7 +259,7 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
254259
# FIXME: Why can't we write to anything other than cmovetraj.txt or
255260
# /tmp/cmovetraj.txt with CBiRRT?
256261
traj_path = 'cmovetraj.txt'
257-
args += [ 'filename', traj_path ]
262+
args += ['filename', traj_path]
258263
args_str = ' '.join(args)
259264

260265
with CollisionOptionsStateSaver(self.env.GetCollisionChecker(),
@@ -267,12 +272,13 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
267272
# Construct the output trajectory.
268273
with open(traj_path, 'rb') as traj_file:
269274
traj_xml = traj_file.read()
270-
traj = openravepy.RaveCreateTrajectory(self.env, 'GenericTrajectory')
275+
traj = openravepy.RaveCreateTrajectory(
276+
self.env, 'GenericTrajectory')
271277
traj.deserialize(traj_xml)
272278

273279
# Tag the trajectory as constrained if a constraint TSR is present.
274-
if (tsr_chains is not None
275-
and any(tsr_chain.constrain for tsr_chain in tsr_chains)):
280+
if (tsr_chains is not None and
281+
any(tsr_chain.constrain for tsr_chain in tsr_chains)):
276282
SetTrajectoryTags(traj, {Tags.CONSTRAINED: True}, append=True)
277283

278284
# Strip extraneous groups from the output trajectory.
@@ -289,11 +295,10 @@ def ClearIkSolver(self, manip):
289295
if manip.GetIkSolver() is not None:
290296
raise ValueError('Unable to clear IkSolver')
291297

292-
293298
@staticmethod
294299
def serialize_dof_values(dof_values):
295-
return [ str(len(dof_values)),
296-
' '.join([ str(x) for x in dof_values]) ]
300+
return [str(len(dof_values)),
301+
' '.join([str(x) for x in dof_values])]
297302

298303

299304
def SerializeTransform12Col(tm, format='%.5f'):

src/prpy/planning/ompl.py

Lines changed: 28 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -28,11 +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 logging, numpy, openravepy, os, tempfile
31+
import logging
32+
import numpy
33+
import openravepy
3234
from ..util import CopyTrajectory, SetTrajectoryTags
3335
from base import (BasePlanner, PlanningError, UnsupportedPlanningError,
3436
PlanningMethod, Tags)
3537
from openravepy import PlannerStatus
38+
from .cbirrt import SerializeTSRChain
3639

3740
logger = logging.getLogger(__name__)
3841

@@ -49,7 +52,8 @@ def __init__(self, algorithm='RRTConnect'):
4952

5053
if self.planner is None:
5154
raise UnsupportedPlanningError(
52-
'Unable to create "{:s}" planner. Is or_ompl installed?'.format(planner_name))
55+
'Unable to create "{:s}" planner. Is or_ompl installed?'
56+
.format(planner_name))
5357

5458
def __str__(self):
5559
return 'OMPL {0:s}'.format(self.algorithm)
@@ -69,20 +73,21 @@ def PlanToConfiguration(self, robot, goal, **kw_args):
6973
def PlanToTSR(self, robot, tsrchains, **kw_args):
7074
"""
7175
Plan using the given set of TSR chains with OMPL.
72-
@param robot
76+
@param robot
7377
@param tsrchains A list of tsrchains to use during planning
7478
@param return traj
7579
"""
7680
return self._TSRPlan(robot, tsrchains, **kw_args)
7781

7882
def _Plan(self, robot, goal=None, timeout=30., shortcut_timeout=5.,
79-
continue_planner=False, ompl_args=None,
83+
continue_planner=False, ompl_args=None,
8084
formatted_extra_params=None, **kw_args):
8185
extraParams = '<time_limit>{:f}</time_limit>'.format(timeout)
8286

8387
if ompl_args is not None:
84-
for key,value in ompl_args.iteritems():
85-
extraParams += '<{k:s}>{v:s}</{k:s}>'.format(k=str(key), v=str(value))
88+
for key, value in ompl_args.iteritems():
89+
extraParams += '<{k:s}>{v:s}</{k:s}>'.format(
90+
k=str(key), v=str(value))
8691

8792
if formatted_extra_params is not None:
8893
extraParams += formatted_extra_params
@@ -95,42 +100,38 @@ def _Plan(self, robot, goal=None, timeout=30., shortcut_timeout=5.,
95100

96101
traj = openravepy.RaveCreateTrajectory(self.env, 'GenericTrajectory')
97102

98-
# Plan. We manually lock and unlock the environment because the context
99-
# manager is currently broken on cloned environments.
100-
self.env.Lock()
101-
try:
103+
# Plan.
104+
with self.env:
102105
if (not continue_planner) or (not self.setup):
103106
self.planner.InitPlan(robot, params)
104107
self.setup = True
105108

106109
status = self.planner.PlanPath(traj, releasegil=True)
107-
if status not in [ PlannerStatus.HasSolution,
108-
PlannerStatus.InterruptedWithSolution ]:
109-
raise PlanningError('Planner returned with status {0:s}.'.format(
110-
str(status)))
111-
finally:
112-
self.env.Unlock()
110+
if status not in [PlannerStatus.HasSolution,
111+
PlannerStatus.InterruptedWithSolution]:
112+
raise PlanningError('Planner returned with status {0:s}.'
113+
.format(str(status)))
113114

114115
return traj
115116

116117
def _TSRPlan(self, robot, tsrchains, **kw_args):
117-
118118
extraParams = ''
119119
for chain in tsrchains:
120-
extraParams += '<{k:s}>{v:s}</{k:s}>'.format(k = 'tsr_chain', v=chain.serialize())
121-
120+
extraParams += '<{k:s}>{v:s}</{k:s}>'.format(
121+
k='tsr_chain', v=SerializeTSRChain(chain))
122+
122123
return self._Plan(robot, formatted_extra_params=extraParams, **kw_args)
123124

124125

125126
class RRTConnect(OMPLPlanner):
126127
def __init__(self):
127128
OMPLPlanner.__init__(self, algorithm='RRTConnect')
128129

129-
def _SetPlannerRange(robot, ompl_args=None):
130+
def _SetPlannerRange(self, robot, ompl_args=None):
130131
from copy import deepcopy
131132

132133
if ompl_args is None:
133-
ompl_args = {}
134+
ompl_args = dict()
134135
else:
135136
ompl_args = deepcopy(ompl_args)
136137

@@ -167,20 +168,18 @@ def PlanToConfiguration(self, robot, goal, ompl_args=None, **kw_args):
167168
@param goal desired configuration
168169
@return traj
169170
"""
170-
171171
ompl_args = self._SetPlannerRange(robot, ompl_args=ompl_args)
172172
return self._Plan(robot, goal=goal, ompl_args=ompl_args, **kw_args)
173173

174174
@PlanningMethod
175175
def PlanToTSR(self, robot, tsrchains, ompl_args=None, **kw_args):
176176
"""
177-
Plan using the given TSR chains with OMPL.
177+
Plan using the given TSR chains with OMPL.
178178
@param robot
179179
@param tsrchains A list of TSRChain objects to respect during planning
180180
@param ompl_args ompl RRTConnect specific parameters
181181
@return traj
182182
"""
183-
184183
ompl_args = self._SetPlannerRange(robot, ompl_args=ompl_args)
185184
return self._TSRPlan(robot, tsrchains, ompl_args=ompl_args, **kw_args)
186185

@@ -206,7 +205,7 @@ def ShortcutPath(self, robot, path, timeout=1., **kwargs):
206205
output_path = CopyTrajectory(path, env=self.env)
207206

208207
extraParams = '<time_limit>{:f}</time_limit>'.format(timeout)
209-
208+
210209
params = openravepy.Planner.PlannerParameters()
211210
params.SetRobotActiveJoints(robot)
212211
params.SetExtraParameters(extraParams)
@@ -216,10 +215,10 @@ def ShortcutPath(self, robot, path, timeout=1., **kwargs):
216215
# issue that needs to be fixed in or_ompl.
217216
self.planner.InitPlan(robot, params)
218217
status = self.planner.PlanPath(output_path, releasegil=True)
219-
if status not in [ PlannerStatus.HasSolution,
220-
PlannerStatus.InterruptedWithSolution ]:
221-
raise PlanningError('Simplifier returned with status {0:s}.'.format(
222-
str(status)))
218+
if status not in [PlannerStatus.HasSolution,
219+
PlannerStatus.InterruptedWithSolution]:
220+
raise PlanningError('Simplifier returned with status {0:s}.'
221+
.format(str(status)))
223222

224223
SetTrajectoryTags(output_path, {Tags.SMOOTH: True}, append=True)
225224
return output_path

src/prpy/planning/openrave.py

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -70,9 +70,12 @@ def _Plan(self, robot, goals, maxiter=500, continue_planner=False,
7070
or_args=None, **kw_args):
7171

7272
# Get rid of default postprocessing
73-
extraParams = '<_postprocessing planner=""><_nmaxiterations>0</_nmaxiterations></_postprocessing>'
73+
extraParams = ('<_postprocessing planner="">'
74+
'<_nmaxiterations>0</_nmaxiterations>'
75+
'</_postprocessing>')
7476
# Maximum planner iterations
75-
extraParams += '<_nmaxiterations>{:d}</_nmaxiterations>'.format(maxiter)
77+
extraParams += ('<_nmaxiterations>{:d}</_nmaxiterations>'
78+
.format(maxiter))
7679

7780
if or_args is not None:
7881
for key, value in or_args.iteritems():
@@ -122,7 +125,6 @@ def PlanToConfiguration(self, robot, goal, **kw_args):
122125
@param goal the desired robot joint configuration
123126
@return traj a trajectory from current configuration to specified goal
124127
"""
125-
126128
return self._Plan(robot, goal, **kw_args)
127129

128130
@PlanningMethod

0 commit comments

Comments
 (0)