klampt.plan.robotplanning module
Functions:
|
Returns some options that might be good for your given robot, and whether you want a feasible or just an optimal plan. |
|
Creates a standard CSpace instance for the robot moving in the given world. |
|
Creates a MotionPlan object that can be called to solve a standard motion planning problem for a robot in a world. |
|
Creates a MotionPlan object that can be called to solve a standard motion planning problem for a robot in a world. |
|
Plans a path to reach one or more IK targets. |
|
Launches a "wizard" to help set up or debug a planner. |
|
Deprecated in a future version of Klampt. |
|
Deprecated in a future version of Klampt. |
|
Deprecated in a future version of Klampt. |
|
Deprecated in a future version of Klampt. |
|
Deprecated in a future version of Klampt. |
- klampt.plan.robotplanning.preferred_plan_options(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.
- klampt.plan.robotplanning.make_space(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. Note that if an EmbeddedCSpace is returned, you should create a EmbeddedMotionPlan for greater convenience.
- Return type:
- klampt.plan.robotplanning.plan_to_config(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()
)The underlying configuration space (a RobotCSpace, ClosedLoopRobotCSpace, or EmbeddedRobotCSpace) can be retrieved using the “space” attribute of the resulting MotionPlan object.
- Return type:
- klampt.plan.robotplanning.plan_to_set(world, robot, target, edgeCheckResolution=0.01, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset=None, **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 set.
- 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 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.
Note
The function should accept vectors of the same dimensionality as the robot, not the moving subset. Similarly, the CSpace should have the same dimensionality as 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’, ‘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()
)The underlying configuration space (a RobotCSpace, ClosedLoopRobotCSpace, or EmbeddedRobotCSpace) can be retrieved using the “space” attribute of the resulting MotionPlan object.
- Return type:
- klampt.plan.robotplanning.plan_to_cartesian_objective(world, robot, iktargets, iktolerance=0.001, extraConstraints=[], equalityConstraints=[], equalityTolerance=0.001, ignoreCollisions=[], movingSubset=None, **planOptions)[source]
Plans a path to reach one or more IK targets.
- Parameters:
world (WorldModel) – same as plan_to_config
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()
)The underlying configuration space (a RobotCSpace, ClosedLoopRobotCSpace, or EmbeddedRobotCSpace) can be retrieved using the “space” attribute of the resulting MotionPlan object.
- Return type:
- klampt.plan.robotplanning.wizard(world_or_space_or_plan, moving_object=None, draw_end_effectors=None, draw_infeasible=False, debug_plan_time=30)[source]
Launches a “wizard” to help set up or debug a planner. The wizard will allow you to configure the planner, including the group of moving joints, start and terminal sets, and collision detection settings.
The return value is a configured MotionPlan object, ready to be launched.
The wizard will also allow you to get a Python string that sets up the space and/or invokes the planner.
- Parameters:
world_or_space_or_plan (WorldModel, CSpace, or MotionPlan) – the world containing the moving robot, or the currently configured CSpace or MotionPlan.
moving_object (RobotModel or RigidObjectModel, optional) – if world_or_space_or_plan is a WorldModel, this is the moving object for which you’d like to plan. By default, robot 0 is moving.
draw_end_effectors (list, optional) – if provided, initializes the links to be drawn in the motion plan debugger.
draw_infeasible (bool, optional) – initializes whether the motion plan debugger will show infeasible configurations
debug_plan_time (float, optional) – initializes the planning time in the motion plan debugger.
- Returns:
a properly configured MotionPlan object that can be called to get a motion plan. (see
MotionPlan.planMore()
).- Return type:
- klampt.plan.robotplanning.makeSpace(*args, **kwargs)
Deprecated in a future version of Klampt. Use make_space instead
- klampt.plan.robotplanning.planToCartesianObjective(*args, **kwargs)
Deprecated in a future version of Klampt. Use plan_to_cartesian_objective instead
- klampt.plan.robotplanning.planToConfig(*args, **kwargs)
Deprecated in a future version of Klampt. Use plan_to_config instead
- klampt.plan.robotplanning.planToSet(*args, **kwargs)
Deprecated in a future version of Klampt. Use plan_to_set instead
- klampt.plan.robotplanning.preferredPlanOptions(*args, **kwargs)
Deprecated in a future version of Klampt. Use preferred_plan_options instead