MoveItPlanner.plan_cartesian_motion¶
-
MoveItPlanner.
plan_cartesian_motion
(*args, **kwargs)[source]¶ Calculates a cartesian motion path (linear in tool space).
- Parameters
robot (
compas_fab.robots.Robot
) – The robot instance for which the cartesian motion plan is being calculated.frames_WCF (list of
compas.geometry.Frame
) – The frames through which the path is defined.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 planning group used for calculation. Defaults to the robot’s main planning group.
options (dict, optional) – Dictionary containing the following key-value pairs:
"base_link"
: (str
) Name of the base link."link"
: (str
, optional) The name of the link to calculate the forward kinematics for. Defaults to the group’s end effector link."max_step"
: (float
, optional) The approximate distance between the calculated points. (Defined in the robot’s units.) Defaults to0.01
."jump_threshold"
: (float
, optional) The maximum allowed distance of joint positions between consecutive points. If the distance is found to be above this threshold, the path computation fails. It must be specified in relation to max_step. If this threshold is0
, ‘jumps’ might occur, resulting in an invalid cartesian path. Defaults to \(\pi / 2\)."avoid_collisions"
: (bool
, optional) Whether or not to avoid collisions. Defaults toTrue
."path_constraints"
: (list
ofcompas_fab.robots.Constraint
, 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 toNone
."attached_collision_meshes"
: (list
ofcompas_fab.robots.AttachedCollisionMesh
) Defaults toNone
.
- Returns
compas_fab.robots.JointTrajectory
– The calculated trajectory.