Robot.plan_cartesian_motion

Robot.plan_cartesian_motion(frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None)[source]

Calculate a cartesian motion path (linear in tool space).

Parameters:
frames_WCFlist of compas.geometry.Frame

The frames through which the path is defined.

start_configurationcompas_robots.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.

groupstr, optional

The planning group used for calculation. Defaults to the robot’s main planning group.

use_attached_tool_framebool, optional

If True and there is a tool attached to the planning group, it will use its TCF instead of the T0CF to calculate cartesian paths. Defaults to True.

optionsdict, 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.

  • path_constraints :: list of compas_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.

  • attached_collision_meshes :: list of compas_fab.robots.AttachedCollisionMesh

    Defaults to None.

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

>>> with RosClient() as client:             
#: This doctest can pass locally but persistently fails on CI in GitHub. "roslibpy.core.RosTimeoutError: Failed to connect to ROS"
...     robot = client.load_robot()
...     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