@@ -26,7 +26,7 @@ two subclasses:
26
26
planners, each of which is a ` BasePlanner ` or another ` MetaPlanner `
27
27
28
28
Each planner has one or more * planning methods* , annotated with either the
29
- ` @LockedPlanningMethod ` or `@ClonedPlanningMethod decorator, that look like
29
+ ` @LockedPlanningMethod ` or ` @ClonedPlanningMethod ` decorator, that look like
30
30
ordinary functions. Using these decorators makes other PrPy components
31
31
aware that these methods exist and follow a particular specification that
32
32
allows them to be composed with other PrPy objects automatically. For
@@ -50,10 +50,8 @@ might take a significant amount of time.
50
50
For example, the following code will use OMPL to plan ` robot ` 's active DOFs
51
51
from their current values to to the ` goal_config ` configuration:
52
52
53
- ``` python
54
- planner = OMPLPlanner(' RRTConnect' )
55
- output_path = planner.PlanToConfiguration(robot, goal_config)
56
- ```
53
+ planner = OMPLPlanner('RRTConnect')
54
+ output_path = planner.PlanToConfiguration(robot, goal_config)
57
55
58
56
As this is a ` @ClonedPlanningMethod ` , ` robot.GetEnv() ` is cloned into the
59
57
the ` planner.env ` planning environment. Planning occurs within this cloned
@@ -96,7 +94,7 @@ planners:
96
94
a list of ranked IK solutions
97
95
- ` NamedPlanner ` : plan to a named configuration associated with the robot
98
96
99
- See the Python docstrings the above classes for more information.
97
+ See the Python docstrings in the above classes for more information.
100
98
101
99
102
100
### Common Planning Methods
@@ -175,33 +173,27 @@ randomized planners. However, these algorithms are not probabilistically
175
173
complete and can get stuck in local minima. You can mitigate this by using the
176
174
` Sequence ` planner to first call CHOMP, then fall back on RRT-Connect:
177
175
178
- ``` python
179
- planner = Sequence(CHOMPPlanner(), OMPLPlanner(' RRTConnect' ))
180
- path = planner.PlanToConfiguration(robot, goal)
181
- ```
176
+ planner = Sequence(CHOMPPlanner(), OMPLPlanner('RRTConnect'))
177
+ path = planner.PlanToConfiguration(robot, goal)
182
178
183
179
Unfortunately, this means that RRT-Connect does not start planning until CHOMP
184
180
has already failed to find a solution. Instead of using ` Sequence ` , we can use
185
181
the ` Ranked ` meta-planner to plan with both planners in parallel. Just as
186
182
before, the meta-planner will immediately return CHOMP's solution if it returns
187
183
success. However, RRT-Connect will have a head-start if CHOMP fails:
188
184
189
- ``` python
190
- planner = Ranked(CHOMPPlanner(), OMPLPlanner(' RRTConnect' ))
191
- path = planner.PlanToConfiguration(robot, goal)`
192
- ```
185
+ planner = Ranked(CHOMPPlanner(), OMPLPlanner('RRTConnect'))
186
+ path = planner.PlanToConfiguration(robot, goal)`
193
187
194
188
In other cases, a meta-planner can be used to combine the disparate
195
189
capabilities of multiple planenrs. For example, SBPL is currently the only
196
190
planner included with PrPy that supports planning for affine DOFs. We can use a
197
191
meta-planner to combine OMPL's support for ` PlanToConfiguration ` with SBPL's
198
192
support for ` PlanToBasePose ` :
199
193
200
- ``` python
201
- planner = Sequence(OMPLPlanner(' RRTConnect' ), SBPLPlanner())
202
- path1 = planner.PlanToConfiguration(robot, goal)
203
- path2 = planner.PlanToBasePose(robot, goal_pose)
204
- ```
194
+ planner = Sequence(OMPLPlanner('RRTConnect'), SBPLPlanner())
195
+ path1 = planner.PlanToConfiguration(robot, goal)
196
+ path2 = planner.PlanToBasePose(robot, goal_pose)
205
197
206
198
## Perception Pipeline
207
199
@@ -213,16 +205,15 @@ There is a `prpy.perception.base.PerceptionModule` class which is extended by ev
213
205
routine. Every routine has some common methods for perception, which are annotated with
214
206
` @PerceptionMethod ` . Here is an example call (should happen in a typical herbpy console):
215
207
216
- ``` python
217
- from prpy.perception.apriltags import ApriltagsModule
208
+ from prpy.perception.apriltags import ApriltagsModule
209
+
210
+ adetector = ApriltagsModule(marker_topic='/apriltags_kinect2/marker_array',
211
+ marker_data_path=FindCatkinResource('pr_ordata','data/objects/tag_data.json'),
212
+ kinbody_path=FindCatkinResource('pr_ordata','data/objects'),
213
+ destination_frame='/map',
214
+ detection_frame='/head/kinect2_rgb_optical_frame')
215
+ detected_objects = adetector.DetectObjects(robot)
218
216
219
- adetector = ApriltagsModule(marker_topic = ' /apriltags_kinect2/marker_array' ,
220
- marker_data_path = FindCatkinResource(' pr_ordata' ,' data/objects/tag_data.json' ),
221
- kinbody_path = FindCatkinResource(' pr_ordata' ,' data/objects' ),
222
- destination_frame = ' /map' ,
223
- detection_frame = ' /head/kinect2_rgb_optical_frame' )
224
- detected_objects = adetector.DetectObjects(robot)
225
- ```
226
217
IMPORTANT - Most of these methods require some underlying CPP server to be running, before calls can be
227
218
made to the PrPy detector.
228
219
@@ -298,49 +289,41 @@ environments during cloning correctly to avoid introducing a race condition.
298
289
In the simplest case, the ` Clone ` context manager creates an internal,
299
290
temporary environment that is not re-used between calls:
300
291
301
- ``` python
302
- with Clone(env) as cloned_env:
303
- robot = cloned_env.GetRobot(' herb' )
304
- # ...
305
- ```
292
+ with Clone(env) as cloned_env:
293
+ robot = cloned_env.GetRobot('herb')
294
+ # ...
306
295
307
296
The same context manager can be used to clone into an existing environment. In
308
297
this case, the same target environment can be used by multiple calls. This
309
298
allows OpenRAVE to re-use the environments resources (e.g. collision
310
299
tri-meshes) and can dramatically improve performance:
311
300
312
- ``` python
313
- clone_env = openravepy.Environment()
301
+ clone_env = openravepy.Environment()
314
302
315
- with Clone(env, clone_env = clone_env):
316
- robot = cloned_env.GetRobot(' herb' )
317
- # ...
318
- ```
303
+ with Clone(env, clone_env=clone_env):
304
+ robot = cloned_env.GetRobot('herb')
305
+ # ...
319
306
320
307
Often times, the cloned environment must be immediately locked to perform
321
308
additional setup. This introduces a potential race condition between ` Clone `
322
309
releasing the lock and the code inside the ` with ` -block acquiring the lock. To
323
310
avoid this, use the ` lock ` argument to enter the ` with ` -block without releasing
324
311
the lock:
325
312
326
- ``` python
327
- with Clone(env, lock = True ) as cloned_env:
328
- robot = cloned_env.GetRobot(' herb' )
329
- # ...
330
- ```
313
+ with Clone(env, lock=True) as cloned_env:
314
+ robot = cloned_env.GetRobot('herb')
315
+ # ...
331
316
332
317
In this case, the cloned environment will be automatically unlocked when
333
318
exiting the ` with ` -statement. This may be undesirable if you need to explicitly
334
319
unlock the environment inside the ` with ` -statement. In this case, you may pass
335
320
the ` unlock=False ` flag. In this case, you ** must** explicitly unlock the
336
321
environment inside the ` with ` -statement:
337
322
338
- ``` python
339
- with Clone(env, lock = True , unlock = False ) as cloned_env:
340
- robot = cloned_env.GetRobot(' herb' )
341
- env.Unlock()
342
- # ...
343
- ```
323
+ with Clone(env, lock=True, unlock=False) as cloned_env:
324
+ robot = cloned_env.GetRobot('herb')
325
+ env.Unlock()
326
+ # ...
344
327
345
328
346
329
### Cloned Helper Function
@@ -349,96 +332,84 @@ It is frequently necessary to find an object in a cloned environment that
349
332
refers to a particular object in the parent environment. This code frequently
350
333
looks like this:
351
334
352
- ``` python
353
- with Clone(env) as cloned_env:
354
- cloned_robot = cloned_env.GetRobot(robot.GetName())
355
- # ...
356
- ```
335
+ with Clone(env) as cloned_env:
336
+ cloned_robot = cloned_env.GetRobot(robot.GetName())
337
+ # ...
357
338
358
339
The ` prpy.clone.Cloned ` helper function handles this name resolution for most
359
340
OpenRAVE data types (including ` Robot ` , ` KinBody ` , ` Link ` , and ` Manipulator ` ).
360
341
This function accepts an arbitrary number of input parameters---of the
361
342
supported types---and returns the corresponding objects in ` Clone ` d
362
343
environment. For example, the above code can be re-written as:
363
344
364
- ``` python
365
- with Clone(env) as cloned_env:
366
- cloned_robot = Cloned(robot)
367
- # ...
368
- ```
345
+ with Clone(env) as cloned_env:
346
+ cloned_robot = Cloned(robot)
347
+ # ...
369
348
370
349
If multiple ` Clone ` context managers are nested, the ` Cloned ` function returns
371
350
the corresponding object in the inner-most block:
372
351
373
- ``` python
374
- with Clone(env) as cloned_env1:
375
- cloned_robot1 = Cloned(robot) # from cloned_env1
376
- # ...
377
-
378
- with Clone(env) as cloned_env2:
379
- cloned_robot2 = Cloned(robot) # from cloned_env2
352
+ with Clone(env) as cloned_env1:
353
+ cloned_robot1 = Cloned(robot) # from cloned_env1
380
354
# ...
381
-
382
- # ...
383
- cloned_robot3 = Cloned(robot) # from cloned_env1
384
- ```
355
+
356
+ with Clone(env) as cloned_env2:
357
+ cloned_robot2 = Cloned(robot) # from cloned_env2
358
+ # ...
359
+
360
+ # ...
361
+ cloned_robot3 = Cloned(robot) # from cloned_env1
385
362
386
363
The ` Cloned ` function only works if it is called from the same thread in which
387
364
the ` Clone ` context manager was created. If this is not the case, you can still
388
365
use the ` Cloned ` helper function by explicitly passing an environment:
389
366
390
- ``` python
391
- with Clone(env) as cloned_env:
392
- def fn (body , e ):
393
- cloned_robot = Cloned(body, clone_env = e)
394
- # ...
367
+ with Clone(env) as cloned_env:
368
+ def fn(body, e):
369
+ cloned_robot = Cloned(body, clone_env=e)
370
+ # ...
395
371
396
- thread = Thread(target = fn, args = (body, cloned_env))
397
- thread.start()
398
- thread.join()
399
- ```
372
+ thread = Thread(target=fn, args=(body, cloned_env))
373
+ thread.start()
374
+ thread.join()
400
375
401
376
Finally, as a convenience, the ` Cloned ` function can be used to simultaneously
402
377
resolve multiple objects in one statement:
403
378
404
- ``` python
405
379
with Clone(env) as cloned_env:
406
380
cloned_robot, cloned_body = Cloned(robot, body)
407
381
# ...
408
- ```
409
382
410
383
411
384
## Concurrent Execution
412
385
413
386
PrPy has native support for [ futures] ( http://en.wikipedia.org/wiki/Futures_and_promises ) and
414
387
[ coroutines] ( http://en.wikipedia.org/wiki/Coroutine ) to simplify concurrent programming. A
415
388
_ future_ encapsulates the execution of a long-running task. We use the concurrency primitives
416
- provided by the [ ` trollius ` module] ( http://trollius.readthedocs.org/en/latest/ using.html ) ,
389
+ provided by the [ ` trollius ` module] ( http://trollius.readthedocs.org/using.html ) ,
417
390
which is a Python 2 backport of the [ ` asyncio ` module] ( https://docs.python.org/3/library/asyncio.html )
418
391
from Python 3.
419
392
420
393
We can use these primitives to parallelize planning and execution:
421
394
422
- ``` python
423
- @coroutine
424
- def do_plan (robot ):
425
- # Plan to goal1 and start executing the trajectory.
426
- path1 = yield From(robot.PlanToEndEffectorPose(goal1, execute = False ))
427
- exec1_future = robot.ExecutePath(path1)
428
-
429
- # Plan from goal1 to goal2.
430
- robot.SetDOFValues(GetLastWaypoint(path1))
431
- path2 = yield From(robot.PlanToEndEffectorPope(goal2, execute = False ))
432
-
433
- # Wait for path1 to finish executing, then execute path2.
434
- exec1 = yield From(exec1_future)
435
- exec2 = yield From(robot.ExecutePath(path2))
436
-
437
- raise Return(path1, path2)
438
-
439
- loop = trollius.get_event_loop()
440
- path = loop.run_until_complete(do_plan(robot))
441
- ```
395
+ @coroutine
396
+ def do_plan(robot):
397
+ # Plan to goal1 and start executing the trajectory.
398
+ path1 = yield From(robot.PlanToEndEffectorPose(goal1, execute=False))
399
+ exec1_future = robot.ExecutePath(path1)
400
+
401
+ # Plan from goal1 to goal2.
402
+ robot.SetDOFValues(GetLastWaypoint(path1))
403
+ path2 = yield From(robot.PlanToEndEffectorPope(goal2, execute=False))
404
+
405
+ # Wait for path1 to finish executing, then execute path2.
406
+ exec1 = yield From(exec1_future)
407
+ exec2 = yield From(robot.ExecutePath(path2))
408
+
409
+ raise Return(path1, path2)
410
+
411
+ loop = trollius.get_event_loop()
412
+ path = loop.run_until_complete(do_plan(robot))
442
413
443
414
## Method Binding
444
415
@@ -449,17 +420,15 @@ types, including: `KinBody`, `Robot`, `Link`, and `Joint`.
449
420
This may appear trivial to accomplish using ` setattr ` . However, this is
450
421
actually quite challenging to implement because OpenRAVE's Python bindings for
451
422
these classes are automatically generated as [ Boost.Python
452
- bindings] ( www.boost.org/doc/libs/release/libs/python/ ) that are managed by a
423
+ bindings] ( http:// www.boost.org/doc/libs/release/libs/python/) that are managed by a
453
424
` shared_ptr ` . Each instance of a ` shared_ptr ` returned by C++ is wrapped in a
454
425
separate Python object. As a result, the following code does not work as
455
426
expected:
456
427
457
- ``` python
458
- robot = env.GetRobot(' herb' )
459
- setattr (robot, ' foo' , ' bar' )
460
- robot_ref = env.GetRobot(' herb' )
461
- robot_ref.foo # raises AttributeError
462
- ```
428
+ robot = env.GetRobot('herb')
429
+ setattr(robot, 'foo', 'bar')
430
+ robot_ref = env.GetRobot('herb')
431
+ robot_ref.foo # raises AttributeError
463
432
464
433
PrPy provides the ` prpy.bind.InstanceDeduplicator ` class to work around this
465
434
issue. This class takes advantage of the user data attached to an OpenRAVE
@@ -474,14 +443,12 @@ An object is flagged for de-duplication using the
474
443
` InstanceDeduplicator.add_canonical ` function. The above example can be
475
444
modified to work as follows:
476
445
477
- ``` python
478
- robot = env.GetRobot(' herb' )
479
- InstanceDeduplicator.add_canonical(robot)
446
+ robot = env.GetRobot('herb')
447
+ InstanceDeduplicator.add_canonical(robot)
480
448
481
- setattr (robot, ' foo' , ' bar' )
482
- robot_ref = env.GetRobot(' herb' )
483
- robot_ref.foo # returns 'bar'
484
- ```
449
+ setattr(robot, 'foo', 'bar')
450
+ robot_ref = env.GetRobot('herb')
451
+ robot_ref.foo # returns 'bar'
485
452
486
453
487
454
### Subclass Binding
@@ -497,10 +464,8 @@ This functionality is most frequently used with the generic PrPy subclasses
497
464
provided in the ` prpy.base ` module. For example, the following code adds the
498
465
capabilities of ` prpy.base.Robot ` to an existing robot:
499
466
500
- ``` python
501
- robot = env.GetRobot(' herb' )
502
- bind_subclass(robot, prpy.base.Robot)
503
- ```
467
+ robot = env.GetRobot('herb')
468
+ bind_subclass(robot, prpy.base.Robot)
504
469
505
470
See the docstrings on the classes defined in ` prpy.base ` for more information.
506
471
@@ -546,4 +511,4 @@ This is a non-exhaustive list of contributors:
546
511
- [ Shervin Javdani] ( https://github.com/sjavdani )
547
512
- [ Sidd Srinivasa] ( https://github.com/siddhss5 )
548
513
- [ Stefanos Nikolaidis] ( https://github.com/Stefanos19 )
549
- - [ Shushman Choudhury] ( https://github.com/Shushman )
514
+ - [ Shushman Choudhury] ( https://github.com/Shushman )
0 commit comments