Only released in EOL distros:  

schunk_grippers: schunk_ezn64 | schunk_pg70

Package Summary

Xacro model and usb driver for basic communication with Schunk EZN64 gripper

schunk_grippers: schunk_ezn64 | schunk_pg70

Package Summary

Xacro model and usb driver for basic communication with Schunk EZN64 gripper

Overview

This package is part of schunk_grippers stack. It allows user to control Schunk EZN64 gripper over USB using standard ROS services and provides Xacro model for easier integration with various robots.

Installation

Git clone source to your "catkin_ws/src" folder and catkin_make as usual.

This package depends on libusb1.0-0 library which should be part of ROS installation. To check availibility type:

$ sudo apt-get install libusb-1.0-0

Permissions

By default, the file permissions for the EZN64 gripper device does not permit writing. This often leads to an error "Not able to open a device" or similar. To permanently change the permissions, it is recomended to create a udev rule. Login as root, create a file "20-usb-ezn64.rules", copy the text below and move the file to "/etc/udev/rules.d/" folder.

SUBSYSTEM=="usb"
ATTR{idVendor}=="7358"
ATTR{idProduct}=="371"
ACTION=="add"
MODE:="0666"

Reboot to apply udev changes.

ROS API

ezn64_usb_control

Node for interfacing EZN64 by libusb1.0-0. Provides ROS services for gripper control and publishes actual gripper position to joint_states

Published Topics

joint_states (sensor_msgs/JointState)
  • publishes actual gripper position

Services

schunk_ezn64/reference (std_msgs/Empty)
  • Referencing the gripper
schunk_ezn64/get_error (std_msgs/Empty)
  • Getting actual gripper error
schunk_ezn64/acknowledge_error (std_msgs/Empty)
  • Acknowledging occured error/errors
schunk_ezn64/get_position (std_msgs/Empty)
  • Getting actual gripper position
schunk_ezn64/set_position (std_msgs/Float32)
  • Setting actual gripper position
schunk_ezn64/stop (std_msgs/Empty)
  • Stopping gripper movement

Parameters

vendor_id (std_msgs/UInt16)
  • Vendor ID according to USB conventions
product_id (std_msgs/UInt16)
  • Product ID according to USB conventions
gripper_id (std_msgs/UInt8)
  • Gripper ID according to controller setup

Required tf Transforms

robot_end_linkschunk_ezn64_base_link
  • Connecting gripper to robot

Provided tf Transforms

schunk_ezn64_base_linkschunk_ezn64_finger_1_link
  • Finger 1 link
schunk_ezn64_base_linkschunk_ezn64_finger_2_link
  • Finger 2 link
schunk_ezn64_base_linkschunk_ezn64_finger_3_link
  • Finger 3 link

Usage

Note: Before interfacing Schunk EZN64 gripper from Linux, we highly recomend to use original Windows application Schunk MTS Tool to verify that gripper is fully functional and there are no wiring or other hardware issues.

Launch

To launch the driver node, use the following command:

$ roslaunch schunk_ezn64 ezn64_usb_control.launch

if everything is okay, after typing

$ rostopic echo /joint_states

you should see actual gripper position being published on "joint_states" topic 10 times per second:

header:
  seq: 34
  stamp:
    secs: 1443076490
    nsecs: 513091024
  frame_id: ''
name: ['ezn64_finger_1_joint', 'ezn64_finger_2_joint', 'ezn64_finger_3_joint']
position: [0.011971454620361328, 0.011971454620361328, 0.011971454620361328]
velocity: []
effort: []
---
header:
  seq: 35
  stamp:
    secs: 1443076490
    nsecs: 612699408
  frame_id: ''
name: ['ezn64_finger_1_joint', 'ezn64_finger_2_joint', 'ezn64_finger_3_joint']
position: [0.01197367763519287, 0.01197367763519287, 0.01197367763519287]
velocity: []
effort: []

Note: In case of initialization problems, try to unplug and plug the USB cable again.

Test the driver

To get the list of available services type:

$ rosservice list

If everything is okay, you should notice 6 services being advertised by "ezn64_usb_control" node:

schunk_ezn64/reference
schunk_ezn64/get_error
schunk_ezn64/acknowledge_error
schunk_ezn64/get_position
schunk_ezn64/set_position
schunk_ezn64/stop

These services are ROS user interface to Schunk EZN64 gripper. Except "set_position" all of them use std_msgs::Empty requests, so you don't need to specify any values, just "rosservice call" as in the example below.

get_error service

To test the driver start by calling the get_error service (std_msgs::Empty request):

$ rosservice call /schunk_ezn64/get_error

If no error occured - the driver should respond:

error_code: 0

get_position

To get actual gripper position, call get_position service (std_msgs::Empty request):

$ rosservice call /schunk_ezn64/get_position

Gripper should respond with actual position value in std_msgs::Float32 format:

actual_position: 11.9702377319

set_position

To move the gripper to target position, call set_position service (std_msgs::float32 request):

$ rosservice call /schunk_ezn64/set_position value

where "value" is within a range of <0 - 12> mm. The current driver supports only position control, which means that "goal_velocity" and "goal_acceleration" are permanently set to default values.

If goal_position within a range, the gripper should respond with goal_position being accepted and move to desired position:

goal_accepted: True

reference

To reference gripper, call reference service (std_msgs::Empty request). Referencing may also help in cases you are not able to move the gripper although everything else looks okay:

$ rosservice call schunk_ezn64/reference

Xacro model

To visualize Schunk EZN64 gripper in Rviz use "ezn64_visualize_standalone.launch" file.

$ roslaunch schunk_ezn64 ezn64_visualize_standalone.launch

Since all three fingers are mechanically interlocked, there is only one joint to control the movement of all of them. Use joint_state_publisher GUI to test the movement:

ezn64_standalone.jpg

Wiki: schunk_ezn64 (last edited 2015-09-24 06:46:38 by FrantisekDurovsky)