Overview

This package provides the driver for controlling the Schunk Five Finger Hand with ROS-control.

Installation

Please see the install instructions in the official Github repository. The driver communicates via a RS485-based protocol, for which the Brainbox USB to Serial converters have proven to work well. They are usually distributed together with the hand.

ROS API

svh_ros_control_node

This is the only node that's needed to control the Schunk Five Finger Hand. It uses ROS-control for managing controllers. Most topic and service communication is thus handled through the controller manager, such as publishing joint_states and receiving action goals for the joint_trajectory_controller. The node adds the following topics and services.

Subscribed Topics

connect (std_msgs/Empty)
  • Tries to connect to the hardware when triggered. The hardware will use the serial_device that can be reconfigured via dynamic reconfigure
enable_channel (std_msgs/Int8)
  • Enables a given channel (finger). See channel mapping.

Services

home_reset_offset_all (schunk_svh_msgs/HomeAll)
  • Reset all of the SVH's joints.
home_reset_offset_by_id (schunk_svh_msgs/HomeWithChannels)
  • Reset a subset of the SVH's joints.
set_all_force_limits (schunk_svh_msgs/SetAllChannelForceLimits)
  • Set the force limits for all joints. Each limit is represented by a single float.
set_force_limit_by_id (schunk_svh_msgs/SetChannelForceLimit)
  • Set the force limits for an individual joint

Parameters

~autostart (bool, default: true)
  • If set to true the controller will immediately try to connect to the hardware and start a reset of all the channels (fingers)
~connect_retry_count (int, default: 3)
  • Number of times that we try to connect during startup when not successful.
~serial_device (string, default: /dev/ttyUSB0)
  • Device handle to use for the serial communication, e.g /dev/ttyUSB0
~disable_flags (vector of bool, default: 9 x false)
  • Indicates if a channel (finger) should be disabled. If disabled a finger will not be activated by the hardware but behaves as if everything was fine. This can be used in case a finger has a hardware failure.
~reset_timeout (int, default: 5)
  • Time in seconds after which a reset of a channel (finger) is aborted if the reset current threshold can not be reached. If a channel (finger) needs to reach 300mA for detection of a hard stop but is stuck at 200mA the reset is aborted after reset_timeout seconds.
~finger_reset_speed (double, default: 0.2)
  • Speed of fingers during reset, given as percentage of their usual speed.
/robot_description (urdf model, default: schunk_svh_description/urdf/svh-standalone.urdf.xacro)
  • Urdf model of the hand, including the joints and links describing the svh
~maximal_force (float, default: 0.9)
  • set the max force / current as a percentage of the maximally possible current
~name_prefix (string, default: right_hand)
  • Set either left_hand or right_hand according to your hardware setup.

Additional Information

You'll find additional information under the following links about

Wiki: schunk_svh_ros_driver (last edited 2023-03-29 08:07:09 by HarryArnst)