Robot.plan_cartesian_motion
-
Robot.
plan_cartesian_motion
(frames_WCF, start_configuration=None, group=None, options=None)[source] Calculate a cartesian motion path (linear in tool space).
- Parameters
frames_WCF (
list
ofcompas.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:- max_step ::
float
, optional The approximate distance between the calculated points. (Defined in the robot’s units.) Defaults to
0.01
.
- max_step ::
- 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 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 cartesian motion planner backend implementation for more details.
- Returns
JointTrajectory
– The calculated trajectory.
Examples
>>> robot.client = RosClient() >>> robot.client.run() >>> frames = [Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0]), Frame([0.5, 0.1, 0.6], [1, 0, 0], [0, 1, 0])] >>> start_configuration = Configuration.from_revolute_values([-0.042, 0.033, -2.174, 5.282, -1.528, 0.000]) >>> group = robot.main_group_name >>> options = {'max_step': 0.01, 'jump_threshold': 1.57, 'avoid_collisions': True} >>> trajectory = robot.plan_cartesian_motion(frames, start_configuration, group=group, options=options) >>> len(trajectory.points) > 1 True >>> robot.client.close()