Motion client version 2.0

Overview

The main classes to plan and execute trajectories with xamla_motion are xamla_motion.v2.MoveGroup and xamla_motion.v2.EndEffector. The difference between both classes is the space in which they operate. The xamla_motion.MoveGroup class plans and executes trajectories where the input is defined in joint space. Whereas the xamla_motion.v2.EndEffector class plans and executes trajectories where the input is defined in cartesian/task space.

The version 2.0 is an update to the now deprecated implementation xamla_motion.MoveGroup and xamla_motion.EndEffector. In version 2.0 a lot of API changes are made to improve the usability.

The major change between version 1.0 and 2.0 is that all move methods not directly execute a trajectory or return a stepped motion client but rather return a move operation. This move operations are property containers. It is possible to hand them over and change the properties if needed.

With help of the plan method a operation can be transformed to a executable trajectory. Here again we get the advantage that it is possible to hand this plan over to other functions. Furthermore, we now have the freedom to decide on demand if the trajectory should be executed supervised or unsupervised.

Example:

import asyncio

from pyquaternion import Quaternion
from xamla_motion.data_types import CartesianPath, JointPath, Pose
from xamla_motion.v2 import EndEffector, MoveGroup
from xamla_motion.utility import register_asyncio_shutdown_handler
from xamla_motion import MoveJointsCollisionFreeOperation, MoveCartesianCollisionFreeOperation

# functions for supervised executation


async def next(stepped_motion_client):
    while True:
        await asyncio.sleep(0.1)
        if stepped_motion_client.state:
            stepped_motion_client.step()
            print('progress {:5.2f} percent'.format(
                stepped_motion_client.state.progress))


async def run_supervised(stepped_motion_client):
    print('start supervised execution')

    task_next = asyncio.ensure_future(next(stepped_motion_client))

    await stepped_motion_client.action_done_future
    task_next.cancel()

    print('finished supervised execution')


def main():
    # create move group instance
    move_group = MoveGroup()
    # get default endeffector of the movegroup
    end_effector = move_group.get_end_effector()

    # create cartesian path and equivalent joint path
    t1 = [0.502522, 0.2580, 0.3670]
    q1 = Quaternion(w=0.304389, x=0.5272, y=0.68704, z=0.39666)

    t2 = [0.23795, 0.46845, 0.44505]
    q2 = Quaternion(w=0.212097, x=0.470916, y=0.720915, z=0.462096)

    t3 = [0.6089578, 0.3406782, 0.208865]
    q3 = Quaternion(w=0.231852, x=0.33222, y=0.746109, z=0.528387)

    pose_1 = Pose(t1, q1)
    pose_2 = Pose(t2, q2)
    pose_3 = Pose(t3, q3)

    cartesian_path = CartesianPath([pose_1, pose_2, pose_3])

    joint_path = end_effector.inverse_kinematics_many(cartesian_path,
                                                      False).path

    loop = asyncio.get_event_loop()
    register_asyncio_shutdown_handler(loop)

    async def example_moves():
        print('test MoveGroup class')
        print('----------------          move joints                 -------------------')
        move_joints = move_group.move_joints(joint_path)
        move_joints = move_joints.with_velocity_scaling(0.1)

        move_joints_plan = move_joints.plan()

        await move_joints_plan.execute_async()

        print('----------------        move joints supervised        -------------------')
        move_joints = move_joints.with_velocity_scaling(0.5)
        stepped_motion_client = move_joints.plan().execute_supervised()
        await run_supervised(stepped_motion_client)

        print('----------------      move joints collision free      -------------------')
        move_joints_cf = MoveJointsCollisionFreeOperation(
            move_joints.to_args())

        await move_joints_cf.plan().execute_async()

        print('test EndEffector class')
        print('----------------          move cartesian               -------------------')
        move_cartesian = end_effector.move_cartesian(cartesian_path)
        move_cartesian = move_cartesian.with_velocity_scaling(0.4)

        move_cartesian_plan = move_cartesian.plan()

        await move_cartesian_plan.execute_async()

        print('----------------      move cartesian supervised        -------------------')
        move_cartesian = move_cartesian.with_velocity_scaling(0.8)
        stepped_motion_client = move_cartesian.plan().execute_supervised()
        await run_supervised(stepped_motion_client)

        print('----------------    move cartesian collision free      -------------------')
        move_cartesian_cf = MoveCartesianCollisionFreeOperation(
            move_cartesian.to_args()
        )

        await move_cartesian_cf.plan().execute_async()

    try:
        loop.run_until_complete(example_moves())
    finally:
        loop.close()


if __name__ == '__main__':
    main()

MoveGroup

class xamla_motion.v2.MoveGroup(move_group_name=None, end_effector_name=None, motion_service=None)[source]

Class with encapsulate move functionality for a specific move group

Initialize MoveGroup class

The initialization process is possible with different settings:

move_group_name and end_effector_name are None:

In this case the first available move group and its first end effector is selected automatically. If no move group or end_effector is available exception is raised.

move_group_name is defined and end_effector_name is none:

In this case the initialization routine tries to find the move group with requested name. If it is available create a instance for this move group and the first available end effector as default end effector. Else an exceptions is raised.

move_group is None and end_effector_name is defined:

In this case the initialization routine tries to find the move group with requested end effector. If it is available create a instance for this move group and the requested end effector as default end effector. Else an exceptions is raised.

move_group is defined and also end_effector_name is defined:

In this case the initialization routine tries to find the requested move group with requested end effector. If it is available create a instance for this move group and the requested end effector as default end effector. Else an exceptions is raised.

Parameters
  • move_group_name (Union[None, str]) – If defined name of the move group which this instance should represent

  • end_effector_name (Union[None, str]) – If defined name of the end_effector which should be used as default end_effector

  • motion_service (Union[None, MotionService]) – An instance of MotionService which is used to communicate with the motion server if None a new instance of MotionService is created

Raises
  • TypeError – If motion_service is not of type MotionService or If the other inputs are not str convertable

  • ServiceException – If necessary services to query available move groups and end effectors are not available

  • RuntimeError – If requested move group or end effector not exist or are not available

acceleration_scaling

Default acceleration scaling which is applied if no custom value is provided

collision_check

bool If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed

Type

collision_check

default_plan_parameters

PlanParameters (read only) Instance of PlanParameters from which the limits and settings are used when no specific user input is given

Type

plan_parameters

default_task_space_plan_parameters

TaskSpacePlanParameters (read only) Instance of TaskSpacePlanParameters from which the limits and settings are used when no specific user input is given

Type

task_space_plan_parameters

end_effector_names

List[str] (read only) List of end effectors the move groups contains

Type

end_effector_names

get_current_joint_positions()[source]

Returns the current joint positions of the move group joints

Returns

joint_positions – current joint position of the move group joints

Return type

JointValues

Raises

ServiceException – If Service is not available or finish not successful

get_current_joint_states()[source]

Returns the current joint states of the move group joints

Returns

joint_states – current joint states of the move group joints

Return type

JointStates

Raises

ServiceException – If Service is not available or finish not successful

get_end_effector(name=None)[source]

Get the end effector specified by name or the default end effector if name is not provided

Parameters

name (Union[None, str]) – Name of the end effector which should be returned

Returns

end_effector – Instance of Class EndEffector with requested name

Return type

xamla_motion.v2.EndEffector

Raises

RuntimeError – If no end effector exist with the requested name

ik_jump_threshold

float maximal allowed inverse kinematics jump threshold

Type

ik_jump_threshold

joint_set

JointSet (read only) joint set of the move group

Type

joint_set

max_deviation

Union[None, float]Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space

Type

max_deviation

motion_service

MotionService (read only) return the instance of motion service which is used to communicate via ros which the motion server

Type

motion_service

move_joints(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]

Create MoveJointsOperation for target joint positions

Parameters
  • target (Union[JointValues, JointPath]) – Target joint positions or target JointPath

  • velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint velocities If None the MoveGroup default is used

  • collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used

  • max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used

  • acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint accelerations If None the MoveGroup default is used

Returns

move_joint_operations – Instance of MoveJointsOperation

Return type

MoveJointsOperation

Raises

TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types

move_joints_collision_free(target, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]

Create MoveJointsCollisionFreeOperation for target joint positions

Parameters
  • target (Union[JointValues, JointPath]) – Target joint positions or target JointPath

  • velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint velocities If None the MoveGroup default is used

  • collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used

  • max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used

  • acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint accelerations If None the MoveGroup default is used

Returns

Instance of MoveJointsCollisionFreeOperation

Return type

MoveJointsCollisionFreeOperation

Raises

TypeError – If target is not one of types JointValues, JointPath If all other inputs are not convertable to specified types

name

str (read only) move group name

Type

name

sample_resolution

float Trajectory point sampling frequency If value smaller one in seconds else in Hz

Type

sample_resolution

selected_end_effector

str (read only) Name of the currently selected end effector

Type

selected_end_effector

set_default_end_effector(end_effector_name)[source]

Set one of the end effector from the list of available ones as default

Parameters

end_effector_name (str convertable) – Name of the end effector which should be now the default end effector of this move group

Raises
  • TypeError – If end_effector_name is not str convertable

  • RuntimeError – If the input end effector name is not available

velocity_scaling

Default velocity scaling which is applied if no custom value is provided

EndEffector

class xamla_motion.v2.EndEffector(move_group, end_effector_name, end_effector_link_name)[source]

Class with encapsulate move functionality for a specific end effector

Initialize EndEffector class

Parameters
  • move_group (xamla_motion.v2.MoveGroup) – Instance of move group where the endeffector belongs to

  • end_effector_name (str_convertable) – If defined name of the end_effector which should for which a instance of EndEffector is created and which is selected as default for the move group

  • end_effector_link_name (str convertable) – name of the end effector link

Raises
  • TypeError – If move_group is not of type MoveGroup or If the other inputs are not str convertable

  • ServiceException – If necessary services to query available move groups and end effectors are not available

  • RuntimeError – If requested move group or end effector not exist or are not available

compute_pose(joint_values)[source]

compute pose from joint values / configuration

Parameters

joint_values (JointValues) – Joint configuration of the robot which should be transformed to a cartesian pose

Returns

pose – An instance of Pose which represents the joint configuration of joint_values as a pose in cartesian space

Return type

Pose

Raises
  • ServiceException – If query services from motion server are not available or finish unsuccessfully

  • TypeError – If joint_values is not of expected type JointValues

static from_end_effector_name(end_effector_name)[source]

Creates an instance of MoveGroup and select the correct instance of EndEffector

Parameters

end_effector_name (str convertable) – Name of the end_effector for which a instance of EndEffector should be created

Returns

Instance of EndEffector for end effector with the name specified by end_effector name (instance is also hold by the created move_group)

Return type

xamla_motion.v2.EndEffector

Raises
  • TypeError – If end_effector_name ist not convertable to str

  • RuntimeError – If it is not possible to create an instance of EndEffector because the end effector specified by end_effector_name is not available

get_current_pose()[source]

Returns the current pose of the end effector

Returns

pose – An instance of Pose which represents the current end effector pose

Return type

Pose

Raises

ServiceException – If query services from motion server are not available or finish unsuccessfully

inverse_kinematics(pose, collision_check, seed=None, timeout=None, const_seed=False, attempts=1)[source]

inverse kinematic solutions for one pose

Parameters
  • poses (Union[Pose, CartesianPath]) – Poses to transform to joint space

  • collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed

  • seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration

  • timeout (Union[None, datatime.timedelta] (optional)) – timeout

  • const_seed (bool (optional default False)) – Determines if for each pose in poses the same seed should be used

  • attempts (int (optional default 1)) – number of attempts to find solution

Returns

Instance of JointValues with a found solution

Return type

JointValues

Raises
  • TypeError – If poses is not of correct type

  • ServiceException – If query service is not available

inverse_kinematics_many(poses, collision_check, seed=None, timeout=None, const_seed=False, attempts=1)[source]

inverse kinematic solutions for many poses

Parameters
  • poses (Union[Pose, CartesianPath]) – Poses to transform to joint space

  • collision_check (Union[None, bool]) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed

  • seed (Union[None, JointValues] (optional)) – Numerical seed to control joint configuration

  • timeout (Union[None, datatime.timedelta] (optional)) – timeout

  • const_seed (bool (optional default False)) – Determines if for each pose in poses the same seed should be used

  • attempts (int (optional default 1)) – number of attempts to find solution

Returns

Instance of IkResult with all found solutions as a JointPath and error codes

Return type

IkResult

Raises
  • TypeError – If poses is not of correct type

  • ServiceException – If query service is not available

str end effector link name

Type

link_name

motion_service

MotionService Instance of MotionService which the move group and all end effectors use to communicate with the motion server

Type

motion_service

move_cartesian(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]

Create MoveCartesianOperation for target joint positions

Parameters
  • target (Union[Pose, CartesianPath]) – Target Pose or target CartesianPath

  • seed (Union[None, JointValues] (default None)) – Numerical seed to control joint configuration

  • velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task velocities If None the MoveGroup default is used

  • collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used

  • max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used

  • acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task accelerations If None the MoveGroup default is used

Returns

move_joint_operations – Instance of MoveCartesianOperation

Return type

MoveCartesianOperation

Raises

TypeError – If target is not one of types Pose, CartesianPath If all other inputs are not convertable to specified types

move_cartesian_collision_free(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]

Create MoveCartesianCollisionFreeOperation for target joint positions

Parameters
  • target (Union[Pose, CartesianPath]) – Target Pose or target CartesianPath

  • seed (Union[None, JointValues] (default None)) – Numerical seed to control joint configuration

  • velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task velocities If None the MoveGroup default is used

  • collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used

  • max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used

  • acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task accelerations If None the MoveGroup default is used

Returns

move_joint_operations – Instance of MoveCartesianCollisionFreeOperation

Return type

MoveCartesianCollisionFreeOperation

Raises

TypeError – If target is not one of types Pose, CartesianPath If all other inputs are not convertable to specified types

move_cartesian_linear(target, seed=None, velocity_scaling=None, collision_check=None, max_deviation=None, acceleration_scaling=None)[source]

Create MoveCartesianLinearOperation for target joint positions

Parameters
  • target (Union[Pose, CartesianPath]) – Target Pose or target CartesianPath

  • seed (Union[None, JointValues] (default None)) – Numerical seed to control joint configuration

  • velocity_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task velocities If None the MoveGroup default is used

  • collision_check (Union[None, bool] (default None)) – If true the trajectory planing try to plan a collision free trajectory and before executing a trajectory a collision check is performed If None the MoveGroup default is used

  • max_deviation (Union[None, float] (default None)) – Defines the maximal deviation from trajectory points when it is a fly-by-point in joint space If None the MoveGroup default is used

  • acceleration_scaling (Union[None, float] (default None)) – Scaling factor which is applied on the maximal possible joint and task accelerations If None the MoveGroup default is used

Returns

move_joint_operations – Instance of MoveCartesianLinearOperation

Return type

MoveCartesianLinearOperation

Raises

TypeError – If target is not one of types Pose, CartesianPath If all other inputs are not convertable to specified types

move_group

xamla_motion.v2.MoveGroup Instance of MoveGroup which manages the move group where the end effector belongs to

Type

move_group

name

str (read only) end effector name

Type

name

MoveJointsOperation

class xamla_motion.motion_operations.MoveJointsOperation(args)[source]

Initialization of MoveJointsOperation

Parameters

args (MoveJointsArgs) – move joint args which define the move operation

Returns

Instance of MoveJointsOperation

Return type

MoveJointsOperation

plan()[source]

Planes a trajectory with defined properties

Returns

Instance of Plan which holds the planned trajectory and methods to creates executors for it

Return type

Plan

Raises

ServiceException – If trajectory planning service is not available or finish unsuccessfully

to_args()[source]

Creates an Instance of MoveJointsArgs from this MoveJointsOperation

Returns

MoveJointsArgs which holds the properties of this MoveJointsOperation

Return type

MoveJointsArgs

with_acceleration_scaling(acceleration_scaling)[source]

Creates new instance of MoveJointsOperation with modified velocity limits

Parameters

acceleration_scaling (float convertable) – scale hard acceleration limits by defined factor

Returns

New instance with modified acceleration limits

Return type

MoveJointsOperations

Raises
  • TypeError – If acceleration_scaling is not float convertable

  • ValueError – If acceleration_scaling is not in range 0.0, 1.0

with_args(velocity_scaling=None, collision_check=None, max_deviation=None, sample_resolution=None, acceleration_scaling=None)[source]

Creates new instance of MoveJointsOperations with multiple modified properties

All None assigned arguments take the current property values

Parameters
  • velocity_scaling (float convertable (default None)) – scale hard velocity limits by defined factor

  • collision_check (bool (default None)) – If True collisions with collision objects in worldview are check in the planning stage

  • max_deviation (float convertable) – defines the maximal deviation from trajectory points when it is a fly-by-point in joint space

  • sample_resolution (float convertable) – sampling resolution of trajectory in Hz

  • acceleration_scaling (float convertable) – scale hard acceleration limits by defined factor

Returns

New instance with modified properties

Return type

MoveJointsOperations or child of it (MoveJointsCollisionFreeOperations)

Raises
  • TypeError – If velocity_scaling, max_deviation, sample_resolution and acceleration_scaling are not None or not float convertable

  • ValueError – If velocity_scaling or acceleration scaling are not None and no lie in range 0.0 to 1.0

with_collision_check(collision_check=True)[source]

Creates new instance of MoveJointsOperation with modified collision check flag

Parameters

collision_check (bool (default True)) – If True collisions with collision objects in worldview are check in the planning stage

Returns

New instance with modified collision check flag

Return type

MoveJointsOperations

Raises

TypeError – If collision check is of expected type bool

with_max_deviation(max_deviation)[source]

Creates new instance of MoveJointsOperation with modified max deviation

Parameters

max_deviation (float convertable) – defines the maximal deviation from trajectory points when it is a fly-by-point in joint space

Returns

New instance with modified max deviation

Return type

MoveJointsOperations

Raises

TypeError – If max_deviation is not float convertable

with_sample_resolution(sample_resolution)[source]

Creates new instance of MoveJointsOperation with modified sample resolution

Parameters

sample_resolution (float convertable) – sampling resolution of trajectory in Hz

Returns

New instance with modified sample resolution

Return type

MoveJointsOperations

Raises

TypeError – If sample_resolution is not float convertable

with_start(joint_value)[source]

Creates new instance of MoveJointsOperation with modified start joint value

Parameters

joint_value (JointValues or None) – defines start joint configuration if non current robot state is used

Returns

New instance with modified start value

Return type

MoveJointsOperations

Raises

TypeError – If joint_value is not of expected type JointValue

with_velocity_scaling(velocity_scaling)[source]

Creates new instance of MoveJointsOperation with modified velocity limits

Parameters

velocity_scaling (float convertable) – scale hard velocity limits by defined factor

Returns

New instance with modified velocity limits

Return type

MoveJointsOperations

Raises
  • TypeError – If velocity_scaling is not float convertable

  • ValueError – If velocity_scaling is not in range 0.0, 1.0

MoveCartesianOperation

class xamla_motion.motion_operations.MoveCartesianOperation(args)[source]

Initialization of MoveCartesianOperation

Parameters

args (MoveCartesianArgs) – move cartesian args which define the move operation

Returns

Instance of MoveCartesianOperation

Return type

MoveCartesianOperation

plan()[source]

Planes a trajectory with defined properties

Returns

Instance of Plan which holds the planned trajectory and methods to creates executors for it

Return type

Plan

Raises

ServiceException – If trajectory planning service is not available or finish unsuccessfully

to_args()[source]

Creates an Instance of MoveCartesianArgs from this MoveCartesianOperation

Returns

MoveCartesianArgs which holds the properties of this MoveCartesianOperation

Return type

MoveCartesianArgs

with_acceleration_scaling(acceleration_scaling)[source]

Creates new instance of MoveCartesianOperation with modified velocity limits

Parameters

acceleration_scaling (float convertable) – scale hard acceleration limits by defined factor

Returns

New instance with modified acceleration limits

Return type

MoveCartesianOperations

Raises
  • TypeError – If acceleration_scaling is not float convertable

  • ValueError – If acceleration_scaling is not in range 0.0, 1.0

with_args(velocity_scaling=None, collision_check=None, max_deviation=None, sample_resolution=None, ik_jump_threshold=None, acceleration_scaling=None)[source]

Creates new instance of MoveCartesianOperations with multiple modified properties

All None assigned arguments take the current property values

Parameters
  • velocity_scaling (float convertable (default None)) – scale hard velocity limits by defined factor

  • collision_check (bool (default None)) – If True collisions with collision objects in worldview are check in the planning stage

  • max_deviation (float convertable) – defines the maximal deviation from trajectory points when it is a fly-by-point in joint space

  • sample_resolution (float convertable) – sampling resolution of trajectory in Hz

  • ik_jump_threshold (None or float) – Maximal joint value jump between two consecutively following trajectory points

  • acceleration_scaling (float convertable) – scale hard acceleration limits by defined factor

Returns

New instance with modified properties

Return type

MoveJointsOperations

Raises
  • TypeError – If velocity_scaling, max_deviation, sample_resolution and acceleration_scaling are not None or not float convertable

  • ValueError – If velocity_scaling or acceleration scaling are not None and no lie in range 0.0 to 1.0

with_collision_check(collision_check=True)[source]

Creates new instance of MoveCartesianOperation with modified collision check flag

Parameters

collision_check (bool (default True)) – If True collisions with collision objects in worldview are check in the planning stage

Returns

New instance with modified collision check flag

Return type

MoveCartesianOperations

Raises

TypeError – If collision check is of expected type bool

with_ik_jump_threshold(ik_jump_threshold)[source]

Creates new instance of MoveCartesianOperation with modified ik jump threshold

Parameters

ik_jump_threshold (float convertable) – Maximal joint value jump between two consecutively following trajectory points

Returns

New instance with modified ik jump threshold

Return type

MoveCartesianOperations

Raises

TypeError – If ik_jump_threshold is not float convertable

with_max_deviation(max_deviation)[source]

Creates new instance of MoveCartesianOperation with modified max deviation

Parameters

max_deviation (float convertable) – defines the maximal deviation from trajectory points when it is a fly-by-point in joint space

Returns

New instance with modified max deviation

Return type

MoveCartesianOperations

Raises

TypeError – If max_deviation is not float convertable

with_sample_resolution(sample_resolution)[source]

Creates new instance of MoveCartesianOperation with modified sample resolution

Parameters

sample_resolution (float convertable) – sampling resolution of trajectory in Hz

Returns

New instance with modified sample resolution

Return type

MoveCartesianOperations

Raises

TypeError – If sample_resolution is not float convertable

with_seed(joint_value)[source]

Creates new instance of MoveCartesianOperation with modified seed joint values

Parameters

joint_value (JointValues or None) – defines start joint configuration if None current robot state is used

Returns

New instance with modified seed value

Return type

MoveCartesianOperations

Raises

TypeError – If joint_value is not one of expected types JointValue, Pose, None

with_start(start)[source]

Creates new instance of MoveCartesianOperation with modified start values

Parameters

start (JointValues, Pose or None) – defines trajectory start position if None current robot state is used

Returns

New instance with modified start value

Return type

MoveCartesianOperations

Raises

TypeError – If start is not one of expected types JointValue, Pose, None

with_velocity_scaling(velocity_scaling)[source]

Creates new instance of MoveCartesianOperation with modified velocity limits

Parameters

velocity_scaling (float convertable) – scale hard velocity limits by defined factor

Returns

New instance with modified velocity limits

Return type

MoveCartesianOperations

Raises
  • TypeError – If velocity_scaling is not float convertable

  • ValueError – If velocity_scaling is not in range 0.0, 1.0

Plan

class xamla_motion.motion_operations.Plan(move_group, trajectory, parameters)[source]

Plan holds a planned trajectory and offer methods for path execution

Initialization of Plan

Parameters
Returns

Instance of Plan

Return type

Plan

execute_async()[source]

Executes trajectory asynchronously

Returns

Task – Task which asynchronously execute trajectory

Return type

asyncio.Task

Raises
  • TypeError – If trajectory is not of type JointTrajectory or if collision_check is not convertable to bool

  • ServiceException – If execution ends not successful

execute_supervised()[source]

Creates executor for supervised trajectory execution

Returns

Executor client for supervised trajectory execution

Return type

SteppedMotionClient

move_group

xamla_motion.v2.MoveGroup (read only) Move group which executes the trajectory

Type

move_group

parameters

PlanParameters PlanParameters with which the trajectory was planned

Type

parameters

trajectory

JointTrajectory Trajectory which is the execution target

Type

trajectory