Wiki

  Show EOL distros: 

schunk_modular_robotics: schunk_description | schunk_libm5api | schunk_powercube_chain | schunk_sdh | schunk_simulated_tactile_sensors

Package Summary

This package provides an interface for operating the schunk dexterous hand (SDH), including the tactile sensors.

  • Maintainer status: developed
  • Maintainer: Mathias Luedtke <mdl AT ipa.fhg DOT de>, Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • Author: Mathias Luedtke <mdl AT ipa.fhg DOT de>, Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • License: LGPL
  • Source: git https://github.com/ipa320/schunk_modular_robotics.git (branch: hydro_release_candidate)
schunk_modular_robotics: schunk_description | schunk_libm5api | schunk_powercube_chain | schunk_sdh | schunk_simulated_tactile_sensors

Package Summary

This package provides an interface for operating the schunk dexterous hand (SDH), including the tactile sensors.

  • Maintainer status: maintained
  • Maintainer: Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • Author: Mathias Luedtke <mdl AT ipa.fhg DOT de>, Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • License: Apache 2.0
  • Source: git https://github.com/ipa320/schunk_modular_robotics.git (branch: indigo_release_candidate)
schunk_modular_robotics: schunk_description | schunk_libm5api | schunk_powercube_chain | schunk_sdh | schunk_simulated_tactile_sensors

Package Summary

This package provides an interface for operating the schunk dexterous hand (SDH), including the tactile sensors.

  • Maintainer status: developed
  • Maintainer: Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • Author: Mathias Luedtke <mdl AT ipa.fhg DOT de>, Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • License: Apache 2.0
  • Source: git https://github.com/ipa320/schunk_modular_robotics.git (branch: kinetic_dev)
schunk_modular_robotics: schunk_description | schunk_libm5api | schunk_powercube_chain | schunk_sdh | schunk_simulated_tactile_sensors

Package Summary

This package provides an interface for operating the schunk dexterous hand (SDH), including the tactile sensors.

  • Maintainer status: developed
  • Maintainer: Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • Author: Mathias Luedtke <mdl AT ipa.fhg DOT de>, Florian Weisshardt <fmw AT ipa.fhg DOT de>
  • License: Apache 2.0
  • Source: git https://github.com/ipa320/schunk_modular_robotics.git (branch: kinetic_dev)

Hardware Requirements

To use this package you need a schunk dexterous hand www.schunk-modular-robotics.com with firmware version 0.0.2.18. Other firmware versions may work, but are not officially supported. Alternatively you can use a simulated version without any hardware, see cob_gazebo.

Software Requirements

The installation is tested for Ubuntu 10.04, 10.10, 11.04 and 11.10 using ROS electric. If you discover problems installing them on other platforms, please tell us.

ROS API

The schunk_sdh package provides a configurable node for operating a schunk dexterous hand.

sdh_only

The schunk_sdh node takes in trajectory_msgs/JointTrajectory messages and send this directly to the hardware. The joint states can be received by topics and the sdh can be initialized, stopped or recovered via services.

Action Goal

follow_joint_trajectory_action/goal (control_msgs/FollowJointTrajectoryActionGoal)

Action Result

follow_joint_trajectory_action/result (control_msgs/FollowJointTrajectoryActionResult)

Action Feedback

follow_joint_trajectory_action/feedback (control_msgs/FollowJointTrajectoryActionFeedback)

Subscribed Topics

command (trajectory_msgs/JointTrajectory)

Published Topics

/joint_states (sensor_msgs/JointState)

Services

init (cob_srvs/Trigger) stop (cob_srvs/Trigger) recover (cob_srvs/Trigger) set_operation_mode (cob_srvs/Trigger)

Parameters

~sdhdevicetype (string, default: PCAN) ~sdhdevicestring (string, default: /dev/pcan0) ~dsadevicestring (string, default: Required) ~baudrate (int, default: 1000000) ~joint_names (list of strings, default: Required) /robot_description (urdf model, default: Required)

dsa_only

The dsa_only node publishes data from the tactile sensors in form of schunk_sdh/TactileSensor messages.

Published Topics

tactile_data (schunk_sdh/TactileSensor)

Parameters

~dsadevicestring (string, default: Required) ~polling (bool) ~publish_frequency (float)

Usage/Examples

This package is not intended to be used directly, but with the corresponding launch and yaml files from e.g. schunk_bringup in the schunk_robots stack. For using only the sdh use

roslaunch schunk_bringup sdh_solo.launch

For including the sdh in your overall launch file use

<include file="$(find schunk_bringup)/components/sdh.launch" />

All hardware configuration is done in the schunk_hardware_config package. A sample parameter file for the sdh in "schunk_hardware_config/sdh/config/sdh.yaml" could look like this

sdhdevicetype: PCAN
sdhdevicestring: /dev/pcan0
baudrate: 1000000
joint_names: ['sdh_knuckle_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint']
OperationMode: position

A sample parameter file for the dsa tactile sensors in "schunk_hardware_config/sdh/config/dsa.yaml" could look like this

dsadevicestring: /dev/ttyS0
polling: false
use_rle: true
frequency: 30

Wiki: schunk_sdh (last edited 2013-12-03 08:14:38 by FlorianWeisshardt)