(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Force/Torque sensor with WG035 and pr2_etherCAT

Description: Using Force/Torque sensor with WG035 and pr2_etherCAT

Tutorial Level: INTERMEDIATE

Introduction

An ATI Mini45 force/torque sensor can attached on the back side of the PR2 gripper. The un-amplified analog signal from the sensor goes into a WG035 PCB inside the gripper. The WG035 amplifies the analog signal and converts it to a digital signal. The digital data is passed back to computer through the EtherCAT bus.

Requirements Overview

This is a quick overview of what is required to get force/torque data from ATI Mini45.

Gripper MCB (WG006) Firmware

The gripper MCB needs to be running new 2.xx version of its firmware. This firmware is not compatible with older ROS releases (Electric).

pr2_etherCAT and pr2_ethercat_drivers

The Force/Torque sensor and WG006 FW version 2.xx needs ROS Fuerte (or newer). If using ROS Fuerte, pr2_mechanism version 1.6.1 or better is required.

Hardware

The WG035 and F/T sensor needs to be installed on the PR2 gripper.

Configuration

Calibration parameters are needed to convert between sensor strain-gauge readings and Force/Torque values.

OS and software

There is a configuration tool (pr2-ft-config) available for Ubuntu Precise. To install it, do apt-get update and apt-get install pr2-ft.

Make sure you also have the latest pr2-core-* package for your ROS distribution:

  • pr2-core-fuerte 0.1.9 or newer
  • pr2-core-groovy 0.1.4 or newer
  • pr2-core-hydro 0.1.6 or newer

Tutorial Start

Install the latest version of pr2-core-* and pr2-ft

Update your local apt cache:

  • sudo apt-get update

Install the configuration tool:

  • sudo apt-get install pr2-ft

Install the latest version of pr2-core-* (replace <distro> with your ROS distro):

  • sudo apt-get install pr2-core-<distro>

Configure your F/T sensors

Get the serial number from each of the F/T sensors on your robot. The serial number is printed on a white label on the sensor.

The configuration tool will update the robot's launch files and URDF with the correct information for your sensors.

If you have F/T sensors on both grippers, do (replace <left s/n> and <right s/n> with the serial numbers of your sensors, <distro> with groovy or hydro):

  • sudo pr2-ft-config --left <left s/n> --right <right s/n> --distro <distro>

For example, if your left S/N was FT12000 and your right S/N was FT12001, and your PR2 runs Hydro, you would do:

  • sudo pr2-ft-config --left 12000 --right 12001 --distro hydro

You can also pass only the --left or --right options to the configuration tool. For example, if you only have a F/T sensor on the right gripper, and your PR2 runs Hydro, you would do:

  • sudo pr2-ft-config --right 12001 --distro hydro

If you pass no options to the configuration tool, it will reset your configuration, removing the extra launch parameters and reverting to a URDF without the F/T patches.

  • sudo pr2-ft-config --distro hydro

Special instructions for Ubuntu Lucid

Click here for instructions for Ubuntu Lucid

Getting Electric to work with F/T sensors

Skip this section if using ROS Fuerte. Click here for special instructions if you run Electric

The gripper motor controller board (MCB) uses a newer version of firmware that is not supported by ROS electric. When running electric with firmware version (2.xx), you will get the following error(s).

  • [ERROR] [1352339845.318725911]: WG06 FW version 2 not supported 
    [FATAL] [1352339845.318781493]: Unable to initialize slave #33, product code: 6805006, revision: 83886800, serial: 1097

There is a overlay of pr2_etherCAT drivers that should support gripper FW 2.xx Copy the following to ft_electric.rosinstall. You can download the file with this link.

  • - svn: {local-name: pr2_ethercat_drivers, uri: 'https://code.ros.org/svn/wg-ros-pkg/stacks/pr2_ethercat_drivers/branches/ft_electric'}
    - hg: {local-name: pr2_robot, uri: 'https://kforge.ros.org/pr2robot/hg', version: electric-dev}

Use rosinstall to make overlay:

  • rosinstall ~/ft_electric /opt/ros/electric ft_electric.rosinstall

Now source new rosinstall script and build overlay:

  • source ~/ft_electric/setup.bash
    rosmake pr2_robot

Update to pr2_mechanism 1.6.1 for ROS Fuerte

NOTE: version 1.6.1 of pr2_mechanism has the changes needed. Check CMakesLists.txt:

  • roscd pr2_mechanism
    cat CMakeLists.txt | grep rosbuild

You should see:

  • rosbuild_make_distribution(1.6.1)

If using pr2_mechanism 1.6.0 or earlier, update packages.

  • sudo apt-get update
    sudo apt-get dist-upgrade

Patch URDF

F/T adapters add extra length and angular offset to gripper connection. The extra length can be accounted for by adding an extra link in RDF. However, the anglar displacment causes problems for PR2 inverse kinematics, so an offset of 85 degrees is used with the wrist transmission to cancel it out.

A new linke is also added to the URDF for the Force/Torque sensor. The new frame does not use the axis convention used by the PR2 (X axis forward), but instead used the vendor specified reference frame. In this reference frame, the Z-axis points backwards towards wrist, and X and Y axis are aligned to markings ("+X,+Y) on side of F/T sensor. The data on the force torque topic is aligned to force torque reference frame.

Make a copy of URDF and patch it to add a force/torque link for and angular offset for the wrist transmission. NOTE: At this time, robot_uncalibrated_1.8.2.xml is the newest URDF availble, and may change for a future release.

  • cd /etc/ros/fuerte/urdf
    cp robot_uncalibrated_1.8.2.xml robot_uncalibrated_1.8.2_ft.xml

The patch for adding a left F/T sensor can be downloaded here: robot_urdf_left_ft.patch.

The patch for adding a right F/T sensor can be downloaded here: robot_urdf_right_ft.patch.

Patch the URDF with left F/T sensor:

  • patch -p1 robot_uncalibrated_1.8.2_ft.xml < robot_urdf_left_ft.patch

Change robot.xml to point to patched URDF:

  • rm robot.xml
    ln -s robot_uncalibrated_1.8.2_ft.xml robot.xml

Change robot.launch to enbable F/T sensor and load calibration parameters

Each Force/Torque sensor is calibrated at the factory to create a parameter matrix that maps between sensor readings and force/torque values. ROS parameters must be loaded before pr2_etherCAT is run, so the parameters are available to the driver at start-up.

We've created repository with calibration parameters for all F/T sensors. Checkout this repository with svn:

  • svn co https://code.ros.org/svn/wg-ros-pkg/pr2_mods/pr2_force_torque_calibration

The calibration parameters are different for each Force/Torque sensor. The parameter file is named after force/torque serial number. For force/torque sensor with serial number FT11214 the parameter file with be named ft11214_params.yaml. Also, there is common set of parameters used for the F/T amplifier board that is also needed wg035_revF_params.yaml.

Create directory for storing force/torque calibration parameters

  • mkdir /etc/ros/sensors/ft 

Copy parameters files in /etc/ros/sensors/ft directory. Copy wg035_revF_params.yaml, and ftXXXXX_params.yaml where XXXXX is serial number of force/torque sensor:

  • cp wg035_revF_params.yaml /etc/ros/sensors/ft
    cp ftXXXXX_params.yaml /etc/ros/sensors/ft

Change /etc/ros/fuerte/robot.launch to add something like following. Change ftXXXXX_params.yaml to correct filename for F/T sensor parameters. The following

  •     <!-- Left Force/Torque -->
        <group ns="/realtime_loop/l_gripper_motor/">
         <param name="enable_ft_sensor" value="True" type="bool"/>    
         <param name="enable_pressure_sensor" value="True" type="bool"/>
         <rosparam command="load" file="/etc/ros/sensors/ft/ftXXXXX_params.yaml"/>
         <rosparam command="load" file="/etc/ros/sensors/ft/wg035_revF_params.yaml"/>
       </group>
       <!-- Right Force/Torque -->
       <group ns="/realtime_loop/r_gripper_motor/">
         <param name="enable_ft_sensor" value="True" type="bool"/>    
         <param name="enable_pressure_sensor" value="True" type="bool"/>
         <rosparam command="load" file="/etc/ros/sensors/ft/ftXXXXX_params.yaml"/>
         <rosparam command="load" file="/etc/ros/sensors/ft/wg035_revF_params.yaml"/>
       </group>

This is what robot.launch might look like after being modified:

  • <launch>
    
        <!-- Robot Description --> <param name="robot_description" textfile="/etc/ros/fuerte/urdf/robot.xml" />
    
        <!-- Robot Analyzer --> <rosparam command="load" file="$(find pr2_bringup)/config/pr2_analyzers.yaml" ns="diag_agg" />
    
        <!-- Robot bringup --> <include file="$(find pr2_bringup)/pr2.launch" />
    
        <!-- Web ui --> <include file="$(find webui)/webui.launch" />
    
        <!-- Left Force/Torque -->
        <group ns="/realtime_loop/l_gripper_motor/">
          <param name="enable_ft_sensor" value="True" type="bool"/>    
          <param name="enable_pressure_sensor" value="True" type="bool"/>
          <rosparam command="load" file="/etc/ros/sensors/ft/ft12345_params.yaml"/>
          <rosparam command="load" file="/etc/ros/sensors/ft/wg035_revF_params.yaml"/>
        </group>
    
        <rosparam file="/etc/ros/robot.yaml"/>
    
    </launch> 

Notice the parameter file uses a flag that will enable and disable the F/T sensor functionality:

  • <param name="enable_ft_sensor" value="True" type="bool"/> 

If not specified this flag will default to False and the F/T sensor will not be used.

The parameter file also has a parameter to enable and disable the pressure sensors:

  • <param name="enable_pressure_sensor" value="False" type="bool"/>

If not specified this flag will default to True.

If the pressure sensors are not installed (or needed) they should be disabled with the ROS parameter. The pressure sensors are slow and share the SPI bus with F/T amplifier. When the pressure sensor data is read (every 40ms), it will cause a small glitch in the sampling rate for the F/T sensor.

Recalibate PR2 with new F/T sensors (optional)

Follow the directions here pr2_calibration/Tutorials/Calibrating the PR2

Getting ROS data

Depending on whether the force/torque sensor is installed on right or left arm the ROS topic containing F/T data will differ. Use rostopic list and grep to determine topic name:

  • rostopic list | grep /ft

For a PR2, the topic will either be /ft/r_gripper_motor or /ft/l_gripper_motor.

Try viewing the topic data. The topic type should be geometry_msgs/WrenchStamped

  • rostopic echo /ft/r_gripper_motor

The output should look something like:

  • ---
    header: 
      seq: 84683
      stamp: 
        secs: 1332478266
        nsecs: 775333703
      frame_id: ''
    wrench: 
      force: 
        x: 19.5828911521
        y: 13.7608014027
        z: -70.0375319214
      torque: 
        x: 0.064923969713
        y: -3.26302135565
        z: -0.873719285359
    ---

The F/T data is not zeroed and may have a large offset, typical values are 10N for force values and ?? Nm for torque.

Diagnostics

The driver for the force/torque sensor outputs useful diagnostics information. If the F/T sensor is damaged or a wire is unplugged, the diagnostics will contain a warning. On ROS electric the Force/Torque sensor data will most likely show up in "Other" category. In the future, the sensor data may be placed in the "Sensors" category.

Wiki: ethercat_hardware/Tutorials/UsingForceTorqueSensorWithWG035 (last edited 2014-06-04 12:25:07 by Gheorghe Lisca)