Robot.plan_motion¶
-
Robot.
plan_motion
(goal_constraints, start_configuration=None, group=None, options=None)[source]¶ Calculate a motion path.
- Parameters
goal_constraints (list of
Constraint
) – The goal to be achieved, defined in a set of constraints. Constraints can be very specific, for example defining value domains for each joint, such that the goal configuration is included, or defining a volume in space, to which a specific robot link (e.g. the end-effector) is required to move to.start_configuration (
Configuration
, optional) – The robot’s full configuration, i.e. values for all configurable joints of the entire robot, at the starting position. Defaults to the all-zero configuration.group (
str
, optional) – The name of the group to plan for. Defaults to the robot’s main planning group.options (
dict
, optional) – Dictionary containing the following key-value pairs:- path_constraints ::
list
ofConstraint
, optional Optional constraints that can be imposed along the solution path. Note that path calculation won’t work if the start_configuration violates these constraints. Defaults to
None
.
- path_constraints ::
- attached_collision_meshes ::
list
ofcompas_fab.robots.AttachedCollisionMesh
Defaults to
None
.
- attached_collision_meshes ::
There are additional options that are specific to the backend in use. Check the API reference of the motion planner backend implementation for more details.
- Returns
JointTrajectory
– The calculated trajectory.
Examples
Using position and orientation constraints:
>>> robot.client = RosClient() >>> robot.client.run() >>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1]) >>> tolerance_position = 0.001 >>> tolerances_axes = [math.radians(1)] * 3 >>> start_configuration = Configuration.from_revolute_values([-0.042, 4.295, 0, -3.327, 4.755, 0.]) >>> group = robot.main_group_name >>> goal_constraints = robot.constraints_from_frame(frame, tolerance_position, tolerances_axes, group) >>> robot.attached_tool = None >>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {'planner_id': 'RRTConnectkConfigDefault'}) >>> trajectory.fraction 1.0 >>> len(trajectory.points) > 1 True >>> robot.client.close()
Using joint constraints (to the UP configuration):
>>> robot.client = RosClient() >>> robot.client.run() >>> configuration = Configuration.from_revolute_values([0.0, -1.5707, 0.0, -1.5707, 0.0, 0.0]) >>> tolerances_above = [math.radians(5)] * len(configuration.values) >>> tolerances_below = [math.radians(5)] * len(configuration.values) >>> group = robot.main_group_name >>> goal_constraints = robot.constraints_from_configuration(configuration, tolerances_above, tolerances_below, group) >>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {'planner_id': 'RRTConnectkConfigDefault'}) >>> trajectory.fraction 1.0 >>> len(trajectory.points) > 1 True >>> robot.client.close()