klampt.plan.robotplanning module

class klampt.plan.robotplanning.SubsetMotionPlan(space, subset, q0, type=None, **options)[source]

Bases: klampt.plan.cspace.MotionPlan

An adaptor that “lifts” a motion planner in an EmbeddedCSpace to a higher dimensional ambient space. Used for planning in subsets of robot DOFs.

getPath(milestone1=None, milestone2=None)[source]
klampt.plan.robotplanning.makeSpace(world, robot, edgeCheckResolution=0.01, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset=None)[source]

Creates a standard CSpace instance for the robot moving in the given world.

Parameters:
  • world (WorldModel) – the world in which the robot lives, including obstacles.
  • robot (RobotModel) – the moving robot
  • edgeCheckResolution (float, optional) – the resolution at which edges in the path are checked for feasibility
  • extraConstraints (list, optional) –

    possible extra constraint functions, each of which needs to return True if satisfied.

    Note

    Don’t put cartesian constraints here! Instead place your function in equalityConstraints.

  • equalityConstraints (list, optional) – a list of IKObjectives or equality constraints f(x)=0 that must be satisfied during the motion. Equality constraints may return a float or a list of floats. In the latter case, this is interpreted as a vector function, in which all entries of the vector must be 0.
  • equalityTolerance (float, optional) – a tolerance to which all the equality constraints must be satisfied.
  • ignoreCollisions (list) – a list of ignored collisions. Each element may be a body in the world, or a pair (a,b) where a, b are bodies in the world.
  • movingSubset (optional) – if None, ‘all’, or ‘auto’ (default), all joints will be allowed to move. If this is a list, then only these joint indices will be allowed to move.
Returns:

a C-space instance that describes the robot’s feasible space.

This can be used for planning by creating a cspace.MotionPlan object.

Return type:

(CSpace)

klampt.plan.robotplanning.planToCartesianObjective(world, robot, iktargets, iktolerance=0.001, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset=None, **planOptions)[source]
Parameters:
  • world (WorldModel) – same as planToConfig
  • iktargets (list of IKObjective) – a list of IKObjective instances (see the ik module)
  • iktolerance (float) – a tolerance to which the ik objectives must be satisfied
Returns:

a planner instance that can be called to get a

kinematically-feasible plan. (see MotionPlan.planMore() )

Return type:

(MotionPlan)

klampt.plan.robotplanning.planToConfig(world, robot, target, edgeCheckResolution=0.01, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset='auto', verbose=True, **planOptions)[source]

Creates a MotionPlan object that can be called to solve a standard motion planning problem for a robot in a world. The plan starts from the robot’s current configuration and ends in a target configuration.

Parameters:
  • world (WorldModel) – the world in which the robot lives, including obstacles
  • robot (RobotModel) – the moving robot. The plan start configuration is the robot’s current configuration robot.getConfig().
  • target (list of float) – the desired final configuration of the robot.
  • edgeCheckResolution (float, optional) – the resolution at which edges in the path are checked for feasibility
  • extraConstraints (list, optional) –

    possible extra constraint functions, each of which needs to return True if satisfied.

    Note

    Don’t put cartesian constraints here! Instead place your function in equalityConstraints.

  • equalityConstraints (list, optional) – a list of IKObjectives or equality constraints f(x)=0 that must be satisfied during the motion. Equality constraints may return a float or a list of floats. In the latter case, this is interpreted as a vector function, in which all entries of the vector must be 0.
  • equalityTolerance (float, optional) – a tolerance to which all the equality constraints must be satisfied.
  • ignoreCollisions (list) – a list of ignored collisions. Each element may be a body in the world, or a pair (a,b) where a, b are bodies in the world.
  • movingSubset (optional) – if ‘auto’ (default), only the links that are different between the robot’s current config and target config will be allowed to move. Otherwise, if this is None or ‘all’, all joints will be allowed to move. If this is a list, then only these joint indices will be allowed to move.
  • planOptions (keywords) – keyword options that will be sent to the planner. See the documentation for MotionPlan.setOptions for more details.
Returns:

a planner instance that can be called to get a

kinematically-feasible plan. (see MotionPlan.planMore() )

Return type:

(MotionPlan)

klampt.plan.robotplanning.planToSet(world, robot, target, edgeCheckResolution=0.01, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset=None, **planOptions)[source]

reates a MotionPlan object that can be called to solve a standard motion planning problem for a robot in a world. The plan starts from the robot’s current configuration and ends in a target configuration.

Parameters:
  • world (WorldModel) – the world in which the robot lives, including obstacles
  • robot (RobotModel) – the moving robot. The plan starts from robot.getConfig()
  • target (function or CSpace) – a function f(q) returning a bool which is True if the given RobotModel configuration q is a goal, OR an instance of a CSpace subclass where sample() generates a sample in the target set and feasible(x) tests whether a sample is in the target set. (The CSpace should be of the same dimensionality as the robot, not the moving subset.)
  • edgeCheckResolution (float, optional) – the resolution at which edges in the path are checked for feasibility
  • extraConstraints (list, optional) –

    possible extra constraint functions, each of which needs to return True if satisfied.

    Note

    Don’t put cartesian constraints here! Instead place your function in equalityConstraints.

  • equalityConstraints (list, optional) – a list of IKObjectives or equality constraints f(x)=0 that must be satisfied during the motion. Equality constraints may return a float or a list of floats. In the latter case, this is interpreted as a vector function, in which all entries of the vector must be 0.
  • equalityTolerance (float, optional) – a tolerance to which all the equality constraints must be satisfied.
  • ignoreCollisions (list) – a list of ignored collisions. Each element may be a body in the world, or a pair (a,b) where a, b are bodies in the world.
  • movingSubset (optional) – if ‘auto’, ‘all’, or None (default), all joints will be allowed to move. If this is a list, then only these joint indices will be allowed to move.
  • planOptions (keywords) – keyword options that will be sent to the planner. See the documentation for MotionPlan.setOptions for more details.
Returns:

a planner instance that can be called to get a

kinematically-feasible plan. (see MotionPlan.planMore() )

Return type:

(MotionPlan)

klampt.plan.robotplanning.preferredPlanOptions(robot, movingSubset=None, optimizing=False)[source]

Returns some options that might be good for your given robot, and whether you want a feasible or just an optimal plan.

TODO: base this off of info about the robot, such as dimensionality, joint ranges, etc.