Robot.plan_cartesian_motion

Robot.plan_cartesian_motion(waypoints, start_configuration=None, group=None, options=None)[source]

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

Parameters:
waypointscompas_fab.robots.Waypoints

The waypoints for the robot to follow. For more information on how to define waypoints, see Waypoints (Multiple Points / Segments). In addition, note that not all planning backends support all waypoint types, check documentation of the backend in use for more details.

start_configurationcompas_robots.Configuration, optional

The robot’s full configuration, i.e. values for all configurable joints of the entire robot, at the start of the motion. Defaults to the all-zero configuration.

groupstr, optional

The name of the planning group used for motion planning. Defaults to the robot’s main planning group.

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()
...     target_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])]
...     waypoints = FrameWaypoints(target_frames)
...     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(waypoints,                                                     start_configuration,                                                     group=group,                                                     options=options)
...     len(trajectory.points) > 1
True