Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Renamed collision checker context managers #345

Merged
merged 1 commit into from
Aug 9, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 7 additions & 9 deletions src/prpy/collision.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
)


class SimpleRobotCollisionCheckerContextManager(object):
class SimpleRobotCollisionChecker(object):
"""RobotCollisionChecker which uses the standard OpenRAVE interface.

This RobotCollisionChecker is instantiated with a robot,
Expand Down Expand Up @@ -88,7 +88,7 @@ def VerifyCollisionFree(self):
raise SelfCollisionPlanningError.FromReport(report)


class BakedRobotCollisionCheckerContextManager(object):
class BakedRobotCollisionChecker(object):
"""RobotCollisionChecker which uses a baked collision interface.

When this RobotCollisionChecker is instantiated with a robot,
Expand Down Expand Up @@ -173,22 +173,20 @@ def VerifyCollisionFree(self):
raise CollisionPlanningError.FromReport(report)


class SimpleRobotCollisionChecker(object):
class SimpleRobotCollisionCheckerFactory(object):
def __init__(self, collision_options=CollisionOptions.ActiveDOFs):
self.collision_options = collision_options

def __call__(self, robot):
return SimpleRobotCollisionCheckerContextManager(
robot, self.collision_options)
return SimpleRobotCollisionChecker(robot, self.collision_options)


class BakedRobotCollisionChecker(object):
class BakedRobotCollisionCheckerFactory(object):
def __init__(self, collision_options=CollisionOptions.ActiveDOFs):
self.collision_options = collision_options

def __call__(self, robot):
return BakedRobotCollisionCheckerContextManager(
robot, self.collision_options)
return BakedRobotCollisionChecker(robot, self.collision_options)


DefaultRobotCollisionChecker = SimpleRobotCollisionChecker()
DefaultRobotCollisionCheckerFactory = SimpleRobotCollisionCheckerFactory()
28 changes: 15 additions & 13 deletions src/prpy/planning/cbirrt.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
import openravepy
from ..util import SetTrajectoryTags
from ..collision import (
BakedRobotCollisionChecker,
DefaultRobotCollisionChecker,
SimpleRobotCollisionChecker,
DefaultRobotCollisionCheckerFactory,
BakedRobotCollisionCheckerFactory,
SimpleRobotCollisionCheckerFactory,
)
from base import (BasePlanner, PlanningError, UnsupportedPlanningError,
ClonedPlanningMethod, Tags)
Expand All @@ -43,17 +43,21 @@


class CBiRRTPlanner(BasePlanner):
def __init__(self, robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, robot_checker_factory=None):
super(CBiRRTPlanner, self).__init__()

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.problem = openravepy.RaveCreateProblem(self.env, 'CBiRRT')

if self.problem is None:
raise UnsupportedPlanningError('Unable to create CBiRRT module.')

self.robot_collision_checker = robot_collision_checker
if isinstance(robot_collision_checker, SimpleRobotCollisionChecker):
self.robot_checker_factory = robot_checker_factory
if isinstance(robot_checker_factory, SimpleRobotCollisionCheckerFactory):
self._is_baked = False
elif isinstance(robot_collision_checker, BakedRobotCollisionChecker):
elif isinstance(robot_checker_factory, BakedRobotCollisionCheckerFactory):
self._is_baked = True
else:
raise NotImplementedError(
Expand Down Expand Up @@ -293,10 +297,9 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
args += ['filename', traj_path]
args_str = ' '.join(args)

# Bypass the robot_collision_checker context manager since CBiRRT does
# its own baking in C++.
robot_checker = self.robot_collision_checker(robot)
options = robot_checker.collision_options
# Bypass the context manager since CBiRRT does its own baking in C++.
collision_checker = self.robot_checker_factory(robot)
options = collision_checker.collision_options
with CollisionOptionsStateSaver(env.GetCollisionChecker(), options):
response = self.problem.SendCommand(args_str, True)

Expand All @@ -307,8 +310,7 @@ def Plan(self, robot, smoothingitrs=None, timelimit=None, allowlimadj=0,
# Construct the output trajectory.
with open(traj_path, 'rb') as traj_file:
traj_xml = traj_file.read()
traj = openravepy.RaveCreateTrajectory(
env, 'GenericTrajectory')
traj = openravepy.RaveCreateTrajectory(env, '')
traj.deserialize(traj_xml)

# Tag the trajectory as non-determistic since CBiRRT is a randomized
Expand Down
14 changes: 9 additions & 5 deletions src/prpy/planning/chomp.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
import numpy
import openravepy
from ..util import SetTrajectoryTags, GetLinearCollisionCheckPts
from ..collision import DefaultRobotCollisionChecker
from ..collision import DefaultRobotCollisionCheckerFactory
from .exceptions import (
CollisionPlanningError,
SelfCollisionPlanningError
Expand Down Expand Up @@ -166,11 +166,15 @@ def get_affected_links(body, dof_indices):


class CHOMPPlanner(BasePlanner):
def __init__(self, require_cache=False,
robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, require_cache=False, robot_checker_factory=None):
super(CHOMPPlanner, self).__init__()

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.robot_checker_factory = robot_checker_factory
self.require_cache = require_cache
self.robot_collision_checker = robot_collision_checker

self.setupEnv(self.env)

def setupEnv(self, env):
Expand Down Expand Up @@ -276,7 +280,7 @@ def _Plan(self, robot, sampling_func=VanDerCorputSampleGenerator, **kwargs):
checks = GetLinearCollisionCheckPts(robot, traj, norm_order=2,
sampling_func=sampling_func)

with self.robot_collision_checker(robot) as robot_checker:
with self.robot_checker_factory(robot) as robot_checker:
for t, q in checks:
robot.SetActiveDOFValues(q)
robot_checker.VerifyCollisionFree() # Throws on collision.
Expand Down
39 changes: 21 additions & 18 deletions src/prpy/planning/ompl.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,26 +36,38 @@
ClonedPlanningMethod, Tags)
from openravepy import (
CollisionOptionsStateSaver,
PlannerStatus
PlannerStatus,
)
from ..collision import (
BakedRobotCollisionChecker,
DefaultRobotCollisionChecker,
SimpleRobotCollisionChecker,
BakedRobotCollisionCheckerFactory,
DefaultRobotCollisionCheckerFactory,
SimpleRobotCollisionCheckerFactory,
)
from .cbirrt import SerializeTSRChain

logger = logging.getLogger(__name__)


class OMPLPlanner(BasePlanner):
def __init__(self, algorithm='RRTConnect',
robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, algorithm='RRTConnect', robot_checker_factory=None):
super(OMPLPlanner, self).__init__()

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.setup = False
self.algorithm = algorithm
self.robot_collision_checker = robot_collision_checker

self.robot_checker_factory = robot_checker_factory

if isinstance(robot_checker_factory, SimpleRobotCollisionCheckerFactory):
self._is_baked = False
elif isinstance(robot_checker_factory, BakedRobotCollisionCheckerFactory):
self._is_baked = True
else:
raise NotImplementedError(
'or_ompl only supports Simple and'
' BakedRobotCollisionCheckerFactory.')

planner_name = 'OMPL_{:s}'.format(algorithm)
self.planner = openravepy.RaveCreatePlanner(self.env, planner_name)
Expand All @@ -65,14 +77,6 @@ def __init__(self, algorithm='RRTConnect',
'Unable to create "{:s}" planner. Is or_ompl installed?'
.format(planner_name))

if isinstance(robot_collision_checker, SimpleRobotCollisionChecker):
self._is_baked = False
elif isinstance(robot_collision_checker, BakedRobotCollisionChecker):
self._is_baked = True
else:
raise NotImplementedError(
'or_ompl only supports Simple and BakedRobotCollisionChecker.')

def __str__(self):
return 'OMPL {0:s}'.format(self.algorithm)

Expand Down Expand Up @@ -133,9 +137,8 @@ def _Plan(self, robot, goal=None, tsrchains=None, timeout=30., shortcut_timeout=
self.planner.InitPlan(robot, params)
self.setup = True

# Bypass the robot_collision_checker context manager since or_ompl
# does its own baking in C++.
robot_checker = self.robot_collision_checker(robot)
# Bypass the context manager since or_ompl does its own baking.
robot_checker = self.robot_checker_factory(robot)
options = robot_checker.collision_options
with CollisionOptionsStateSaver(env.GetCollisionChecker(), options):
status = self.planner.PlanPath(traj, releasegil=True)
Expand Down
12 changes: 8 additions & 4 deletions src/prpy/planning/snap.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
ClonedPlanningMethod,
Tags
)
from ..collision import DefaultRobotCollisionChecker
from ..collision import DefaultRobotCollisionCheckerFactory


class SnapPlanner(BasePlanner):
Expand All @@ -52,9 +52,13 @@ class SnapPlanner(BasePlanner):
most commonly used as the first item in a Sequence meta-planner to
avoid calling a motion planner when the trivial solution is valid.
"""
def __init__(self, robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, robot_checker_factory=None):
super(SnapPlanner, self).__init__()
self.robot_collision_checker = robot_collision_checker

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.robot_checker_factory = robot_checker_factory

def __str__(self):
return 'SnapPlanner'
Expand Down Expand Up @@ -176,7 +180,7 @@ def _Snap(self, robot, goal, **kw_args):
norm_order=2,
sampling_func=vdc)

with self.robot_collision_checker(robot) as robot_checker:
with self.robot_checker_factory(robot) as robot_checker:
# Run constraint checks at DOF resolution:
for t, q in checks:
# Set the joint positions
Expand Down
12 changes: 8 additions & 4 deletions src/prpy/planning/tsr.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
UnsupportedPlanningError)
from .base import Tags
from ..util import SetTrajectoryTags
from ..collision import DefaultRobotCollisionChecker
from ..collision import DefaultRobotCollisionCheckerFactory
from openravepy import (
IkFilterOptions,
IkParameterization,
Expand All @@ -58,10 +58,14 @@ def grouper(n, iterable):


class TSRPlanner(BasePlanner):
def __init__(self, delegate_planner=None, robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, delegate_planner=None, robot_checker_factory=None):
super(TSRPlanner, self).__init__()

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.delegate_planner = delegate_planner
self.robot_collision_checker = robot_collision_checker
self.robot_checker_factory = robot_checker_factory

def __str__(self):
if self.delegate_planner is not None:
Expand Down Expand Up @@ -174,7 +178,7 @@ def is_time_available(*args):
# Set ActiveDOFs for IK collision checking. We intentionally
# restore the original collision checking options before calling
# the planner to give it a pristine environment.
with self.robot_collision_checker(robot) as robot_checker:
with self.robot_checker_factory(robot) as robot_checker:
while is_time_available() and len(configurations_chunk) < chunk_size:
# Generate num_candidates candidates and rank them using the
# user-supplied IK ranker.
Expand Down
12 changes: 8 additions & 4 deletions src/prpy/planning/vectorfield.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
import openravepy
from .base import BasePlanner, PlanningError, ClonedPlanningMethod, Tags
from .. import util
from ..collision import DefaultRobotCollisionChecker
from ..collision import DefaultRobotCollisionCheckerFactory
from enum import Enum

logger = logging.getLogger(__name__)
Expand Down Expand Up @@ -74,9 +74,13 @@ def DoesCache(cls, status):


class VectorFieldPlanner(BasePlanner):
def __init__(self, robot_collision_checker=DefaultRobotCollisionChecker):
def __init__(self, robot_checker_factory=None):
super(VectorFieldPlanner, self).__init__()
self.robot_collision_checker = robot_collision_checker

if robot_checker_factory is None:
robot_checker_factory = DefaultRobotCollisionCheckerFactory

self.robot_checker_factory = robot_checker_factory

def __str__(self):
return 'VectorFieldPlanner'
Expand Down Expand Up @@ -547,7 +551,7 @@ def fn_callback(t, q):
nonlocals['exception'] = e
return -1 # Stop.

with self.robot_collision_checker(robot) as robot_checker:
with self.robot_checker_factory(robot) as robot_checker:
# Integrate the vector field to get a configuration space path.
#
# TODO: Tune the integrator parameters.
Expand Down