sr_hand Documentation

logo-shadowDB.png

sr_hand: Shadow Robot Hand ROS interface

This is a ROS interface to the Shadow Robot's robotic hand. It contains both an interface to the real hand (communicating via a CAN interface) and a simulated version of the hand. It also contains an interface to Shadow Robot's muscle arm.

  • Homepage: http://www.shadowrobot.com
  • Introduction

    This is a generic ROS interface used to access and experiment with Shadow Robot's hardware. It can be used either for accessing the real hardware or use a virtual hand to test your algorithm / utilities. It also contains an interface to Shadow Robot's muscle arm.

    How to use this interface

    If you didn't pull the branch in the stacks (.path/to/ros/stacks), don't forget to add the path to the shadow_robot stack to your ROS_PACKAGE_PATH for the relevant packages to be found by ROS. To do this, edit your .bashrc: after the line "source /path/to/ros/setup.sh", add :

    export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:/path/to/shadow_robot
    

    Virtual Hand

    To run the virtual Dextrous Hand, just compile the code:

    rosmake --rosdep-install sr_hand

    Then start the ROS interface, if you want to have a motor hand:

    roslaunch sr_hand srh_motor.launch 

    Otherwise, if it's a muscle hand:

    roslaunch sr_hand srh_muscle.launch 

    Real Hand

    If you have a real Shadow Dextrous Hand, you need to uncomment the relevent region in the CMakelist.txt

    include_directories(/usr/realtime/include/)
    LINK_LIBRARIES(pthread)
    add_library(robot STATIC IMPORTED) 
    set_property(TARGET robot PROPERTY IMPORTED_LOCATION /usr/lib/robot.a)
    rosbuild_add_executable(shadowhand_real src/hand/shadowhand.cpp src/hand/real_shadowhand.cpp src/sr_publisher.cpp 
    src/sr_subscriber.cpp src/hand/real_shadowhand_node.cpp src/sr_diagnosticer.cpp)
    rosbuild_link_boost(shadowhand_real thread)
    target_link_libraries(shadowhand_real robot)
    

    Then compile the code:

    rosmake --rosdep-install sr_hand

    You then need to modify slightly the srh_motor.launch file (or srh_muscle.launch), on line 5 replace virtual by real:

    <node pkg="sr_hand" name="shadowhand" type="shadowhand_real" >
    

    Then start the ROS interface:

    roslaunch sr_hand [srh_motor.launch/srh_muscle.launch] 

    Generic use - Hand

    Once you run either a virtual or real hand, you can use the different tools provided by ROS / Shadow without changing anything on either types of hand.

    If you want to view the hand in rviz, just run

    roslaunch sr_hand [rviz_muscle.launch/rviz_motor.launch]

    You then need to add one robot_model to visualize the current positions of the hand. To do this, click on Add at the bottom left of rviz, then select Robot Model. You can also visualize the targets of the hand by using a second robot_model in rviz. Don't forget to specify the correct topics:

    You should see the model displayed in rviz:

    rosinterface.png

    If you need to monitor the diagnostics published by the hand, you can use the following command:

    rosrun robot_monitor robot_monitor

    .

    Generic use - Arm

    To start the arm with the hand attached, run:

    roslaunch sr_hand [sr_arm_motor.launch/sr_arm_muscle.launch] 

    You can then visualize it in rviz:

    roslaunch sr_hand [rviz_motor.launch/rviz_muscle.launch] 

    You then need to add one robot_model to view the current positions of the arm. You can also visualize the targets of the arm by using a second robot_model in rviz. Don't forget to specify the correct topics:

    Details on how all this is organized

    rosinterface.jpg

    To visualize the current organization of the ros nodes, once you've started the shadowhand node by running one of the above commands, you can run the command

    rxplot
    

    As you can see on this diagram generated by rxplot, the shadowhand publishes to two different joint_states topics: one for the targets, one for the position. The joint_states topic is a topic where the current angle, velocity and effort of each joint is published. Those joint_states topics are then transformed to position information by two different robot_state_publisher, using the file shadowhand.xml which contains the model of Shadow Dextrous Hand. The robot_state_publisher then publishes on the tf topic. This tf topic can then be visualized in rviz. The shadowhand node publishes to the diagnostics topic which is then aggregated by a diagnostic_aggregator node.

    Additional data is also published on the /srh/shadowhand_data topic. If you want to look what's published on a topic, you can either look at a simple example (shadowhand_subscriber.py), or simply use the command:

    rostopic echo /srh/shadowhand_data
    

    To send commands to the shadowhand, you can send messages to the following topics.

    To send information to a topic, you can either use a c++ code or a python code. Please refer to the example: shadowhand_publisher.py.

    For more information regarding those topics, please use the command rostopic info

    Control Graphical Interface

    sr_control_gui is a graphical application which integrates most of the tools needed by the end-user to control Shadow Robot's Hardware.

    How to use the GUI.

    To start the GUI, run:

    rosrun sr_control_gui sr_control_gui
    

    The GUI is organized in tabs :

    Simulation Using Gazebo

    The ROS interface comes with a model which can be used in gazebo. Gazebo is encapsulated in ROS. To compile the ROS version of gazebo, run:

    rosmake --rosdep-install gazebo_worlds
    

    Launching Gazebo and spawning your model

    You then can start any model that you want using the different launchers in launch/gazebo. For instance, if you want to spawn the motor hand in gazebo:

    roslaunch sr_hand gazebo_hand_motor.launch
    
    handgazebo1.jpg

    Making your robot move

    When Gazebo is running with the robot model, you can use motion commands to make the robot move. Assuming you have the hand running (see picture above), you can move FFJ3 (the first finger proximal joint) by running:

    rostopic pub /ffproximal_controller/command std_msgs/Float64 0.6
    

    In this example, ffproximal_controller can be any other hand controller, and 0.6 is the position of the joint, 0 being the lower limit and 1 the higher limit of the allowed motion angle. Back in Gazebo, the finger should be like this:

    handgazebo2.jpg

    Modifying the PID values

    The models that are spawned in Gazebo are moveable thanks to PID controllers, which values are easy to modify, in order to set the behaviour of the robot as you wish. If you want to modify the hand PID values, just modify the model/hand_urdf/hand_controller.yaml file. If you want to modify the arm PID values, modify the model/arm_urdf/arm_controller.yaml file In those files each controller looks like:

    wrist_controller:
      type: robot_mechanism_controllers/JointPositionController
      joint: WRJ2
      pid:
        p: 0.0
        i: 0.0
        d: 0.0
        i_clamp: 1
    

    Modifying the P, I and D values will affect the speed and accuracy of your robot motions. When those values are set, just save the file and run your launch file again to apply the modifications.

    For more information on how to use gazebo in ROS, you should probably have a look at: http://www.ros.org/wiki/simulator_gazebo/Tutorials/Gazebo_ROS_API

    Modifying the Models

    The URDF Models used for the visualization (with Rviz) and the simulation (with Gazebo) are available in model/arm_urdf and model/hand_urdf. The arm and hand models are using xacro macros, which allow different robots to be linked in Gazebo (in order to simulate the behaviour of the arm with the hand at its extremity). If you want to modify something in the models, you have two things to do: change the informations in the right .urdf.xacro file, and then generate the .urdf file that will be used as a model.

    Modify the .urdf.xacro file

    The architecture of the robot is as follows (each robot has a motor version and a muscle version):

    All those parts are represented by "link" tags in the URDF files, and linked between them by "joint" tags. To modify data in a part of the hand, open the right .urdf.xacro file (for example to modify the size of the last part of each finger, you want to open the model/hand_urdf/finger/distal.urdf.xacro). Thus, the modification will be applied to all the identical parts of the hand. Then, just save the file.

    Generate the .urdf file

    the .urdf.xacro model has to be turned into a classic .urdf file to be used by ROS. To generate the good file, use the following command: (this example generates the motor version of the hand)

    rosrun xacro xacro.py -o `rospack find sr_hand`/model/robots/shadowhand_motor.urdf `rospack find sr_hand`/model/robots/xacro/shadowhand_motor.urdf.xacro
    

    The .urdf.xacro robot model which is in the model/robots/xacro directory is turned into an urdf file in the model/robots directory (Warning: the urdf file in the model/robots directory has to exist before running the command, because the order is to overwrite what was in the file)

    Code API

    The classes directly interacting or simulating the Dextrous hand are the following:

    You can find the documentation regarding the different publishers and the subscriber here: shadowhand_publisher::ShadowhandPublisher, shadowhand_subscriber::ShadowhandSubscriber, shadowhand_diagnosticer::ShadowhandDiagnosticer .

    The package also contains a python library to access the ROS interface through easy to use high level python commands. Please refer to shadowhand_ros.py. This library is used to develop the sr_control_gui interface.

    Examples

    There's a few examples in the examples directory in sr_hand. You can have a look at the example link_joints.cpp, or the same example written in python: link_joints.py. To run them, just run the following commands in different terminals:

    roslaunch sr_hand srh_motor.launch 
    roslaunch sr_hand rviz_motor.launch
    rosrun sr_control_gui __init__.py 
    

    and then

    rosrun sr_hand link_joints 
    

    or

    rosrun sr_hand link_joints.py
    

    If you move the joint slider for FFJ3, then MFJ3 will move as well.

     All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


    sr_hand
    Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
    autogenerated on Fri Jan 11 09:32:55 2013