Gripper client

Overview

As the motion client classes represent the interface to plan and execute trajectories the gripper client classes are the interface to control different kinds of gripper. At the moment two kinds are support. The classes xamla_motion.CommonGripperProperties and xamla_motion.CommonGripper represents a common inferface for grippers. Due to this generalization the classes only provide methods to control a gripper in a way that many gripper have in common. The classes xamla_motion.WeissWsgGripperProperties and xamla_motion.WeissWsgGripper represent a specialized interface for the capabilities of a smart gripper like the Weiss WSG series offers.

Example:

import asyncio

from xamla_motion.data_types import MoveGripperResult, WsgCommand, WsgResult
from xamla_motion.gripper_client import (CommonGripper,
                                         CommonGripperProperties,
                                         WeissWsgGripper,
                                         WeissWsgGripperProperties)
from xamla_motion.motion_client import MoveGroup
from xamla_motion.utility import register_asyncio_shutdown_handler


def main():
    ioloop = asyncio.get_event_loop()
    register_asyncio_shutdown_handler(ioloop)

    # create instance of movegroup to provide motion services
    move_group = MoveGroup()

    try:
        print('---------- wsg gripper -------------')

        # create instance of wsg gripper by name
        properties = WeissWsgGripperProperties('wsg50')

        wsg_gripper = WeissWsgGripper(properties, move_group.motion_service)

        print('homeing')
        ioloop.run_until_complete(wsg_gripper.homing())

        print('move gripper')
        ioloop.run_until_complete(wsg_gripper.move(0.1, 0.05, 0.05, True))

        print('perform grasp')
        result = ioloop.run_until_complete(wsg_gripper.grasp(0.02, 0.1, 0.05))

        print('---------- common gripper -------------')
        # create instance of common gripper by name and driver rosnode name
        properties1 = CommonGripperProperties('wsg50', 'xamla/wsg_driver')

        gripper = CommonGripper(properties1, move_group.motion_service)

        print('move')
        result1 = ioloop.run_until_complete(gripper.move(0.1, 0.005))

    finally:
        ioloop.close()


if __name__ == '__main__':
    main()

CommonGripper

class xamla_motion.CommonGripperProperties(name, prefix)[source]

Class with represents the properties of a common gripper

This class holds the service and action names which are necessary to command a specific gripper

Initialization of CommonGripperProperties

Parameters
  • name (str convertable) – Name of a specific gripper in rosvita (Configuration, individual wsg actuator, property Name)

  • prefix (str convertable) – Name of the

Returns

  • CommonGripperProperties – Instance of CommonGripperProperties

    Raises

  • ——

  • TypeError – If name is not str convertable If prefix is not str convertable

command_action_name

str Name of the command action

Type

command_action_name

class xamla_motion.CommonGripper(gripper_properties, motion_service)[source]

Class which represents a gripper controlled by the moveit gripper interface

move(position, max_effort)[source]

Asynchronous action to perform a movement

Initialize common gripper instance

Parameters
  • gripper_properties (CommonGripperProperties) – Properties of this gripper instance. Especially the ros services and action names to control the gripper

  • motion_service (MotionService) – Instance of MotionService to communicate with the motion server via ros

Returns

Instance of CommonGripper

Return type

CommonGripper

Raises

TypeError – If gripper_properties is not of type CommonGripperProperties or if motion_service is not of type MotionService

move(position, max_effort)[source]

Asynchronous action to perform a movement

Parameters
  • position (float convertable) – Requested position in meters

  • max_effort (float convertable) – Force which should maximally applied in Newton

Returns

Result status of a common gripper after the execution of the move action

Return type

MoveGripperResult

Raises
  • TypeError – If inputs are not convertable to specified type

  • ServiceError – If command action server is not available

  • RuntimeError – If action returns with unexpected result

WeissWsgGripper

class xamla_motion.WeissWsgGripperProperties(name, prefix='xamla/wsg_driver')[source]

Property class for Weiss Wsg gripper

This class holds the action and service names for a specific Weiss Wsg gripper

Initialize WeissWsgProperties

Parameters
  • name (str convertable) – Name of a specific gripper in rosvita (Configuration, individual wsg actuator, property Name)

  • prefix (str (default = /xamla/wsg_driver/)) – Prefix of the ros service and action names to control a wsg gripper

Returns

Instance of WeissWsgProperties

Return type

WeissWsgProperties

Raises

TypeError – If name is not str convertable If prefix is not str convertable

control_action_name

str Name of the control action for specific Weiss gripper

Type

control_action_name

set_acc_service_name

str Name of the set acceleration service for specific Weiss gripper

Type

set_acc_name

status_service_name

str Name of the status service for specific Weiss gripper

Type

status_service_name

class xamla_motion.WeissWsgGripper(gripper_properties, motion_service)[source]

WeissWsgGripper class

Represent a Weiss Wsg gripper and his abilities / properties

get_status()[source]

Get current status of the gripper

acknowledge_error()[source]

Asynchronous acknowledge an error

grasp(position, speed, force)[source]

Asynchronous action to perform a grasp

async def homing()

Asynchronous action to home the gripper

move(position, speed, force, stop_on_block)[source]

Asynchronous action to perform a movement

release(self, position, speed)[source]

Asynchronous action to release the gripper from a grasp

stop()[source]

Asynchronous action to perform stop the gripper

set_acceleration(acceleration)[source]

Set gripper acceleration

Initialize Weiss Wsg Gripper instance

Parameters
  • gripper_properties (WeissWsgGripperProperties) – Properties of this gripper instance. Especially the ros services names to control the gripper

  • motion_service (MotionService) – Instance of MotionService to communicate with the motion server via ros

Returns

Instance of WeissWsgGripper

Return type

WeissWsgGripper

Raises
  • TypeError – If gripper_properties is not of type WeissWsgGripperProperties or if motion_service is not of type MotionService

  • ServiceExeption – If status service or set acceleration service are not available

acknowledge_error()[source]

Asynchronous acknowledge an error

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

get_status()[source]

Get current status of the gripper

Returns

status – current status of the gripper

Return type

wsg_50_common.msg Status

Raises

ServiceError – If current service is not available or failed

grasp(position, speed, force)[source]

Asynchronous action to perform a grasp

Parameters
  • position (float convertable) – Requested position in meters

  • speed (float convertable) – Requested speed in m/s

  • force (float convertable) – Force which should maximally applied in Newton

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • TypeError – If inputs are not convertable to specified type

  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

homing()[source]

Asynchronous action to home the gripper

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

move(position, speed, force, stop_on_block)[source]

Asynchronous action to perform a movement

Parameters
  • position (float convertable) – Requested position in meters

  • speed (float convertable) – Requested speed in m/s

  • force (float convertable) – Force which should maximally applied in Newton

  • stop_on_block (bool convertable) – If True stop if maximal force is applied

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • TypeError – If inputs are not convertable to specified type

  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

properties

Properties of this Weiss wsg gripper instance

release(position, speed)[source]

Asynchronous action to release the gripper from a grasp

Parameters
  • position (float convertable) – Requested position in meters

  • speed (float convertable) – Requested speed in m/s

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • TypeError – If inputs are not convertable to specified type

  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

set_acceleration(acceleration)[source]

Set gripper acceleration

Parameters

acceleration (float convertable) – Requested acceleration

Returns

error – If True service call was not successful

Return type

bool

Raises
  • TypeError – If inputs are not convertable to specified type

  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result

stop()[source]

Asynchronous action to perform stop the gripper

Returns

Result status of the Weiss Wsg gripper after the execution of the acknowledge action

Return type

WsgResult

Raises
  • ServiceError – If control action server is not available

  • RuntimeError – If action returns with unexpected result