(!) 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.

How to run pr2_etherCAT

Description: How to run pr2_etherCAT for non-typical setups.

Tutorial Level: INTERMEDIATE

Introduction

If you are working with a PR2 or Texai, there is already a launch file that does what you want. However, if you are working on a new type of robot or a non-standard setup, you may find this tutorial useful.

Get pr2_etherCAT

On ROS Electric, get pr2_etherCAT by installing the ros-electric-pr2-robot

  • sudo apt-get install ros-electric-pr2-robot

On ROS Fuerte, get pr2_etherCAT by installing ros-fuerte-pr2-robot

  • sudo apt-get install ros-fuerte-pr2-robot

Create Minimal URDF

pr2_etherCAT needs a description of the robot (URDF) to run properly. The URDF tutorials provide an explanation of the robot description. However, a minimal description can be used on any type of robot.

Copy the following into a file called robot.xml. The file can be put anywhere, but for simplicity put it in your home directory.

  • <?xml version="1.0"?>
    <robot name="robot1">
      <link name="world" />
      <link name="link1" />
      <joint name="joint1" type="continuous">
        <parent link="world"/>
        <child  link="link1"/>
      </joint>
    </robot>

NOTE: The above description does not provide enough information to allow most controllers to execute.

Determine Ethernet interface

pr2_etherCAT needs to be given the Ethernet interface that the EtherCAT devices are connected to. In Linux, Ethernet interfaces are usually named ethX where X is a number (ie eth0). On the PR2, the EtherCAT interface is named ecat0.

First figure out what network interfaces your computer has. The -a option will show you all the interfaces, whether or not they are enabled.

  • ifconfig -a

This will provide a list like the following :

  • eth0      Link encap:Ethernet  HWaddr 00:1b:21:1d:43:2c  
              inet6 addr: fe80::21b:21ff:fe1d:432c/64 Scope:Link
              UP BROADCAST MULTICAST  MTU:1500  Metric:1
              RX packets:103825453 errors:2 dropped:0 overruns:0 frame:1
              TX packets:107085726 errors:0 dropped:0 overruns:0 carrier:0
              collisions:0 txqueuelen:100 
              RX bytes:550630010 (525.1 MB)  TX bytes:1101330533 (1.0 GB)
              Base address:0xef00 Memory:fdac0000-fdae0000 
    
    eth1      Link encap:Ethernet  HWaddr 00:30:1b:a0:97:b0  
              inet addr:10.0.0.161  Bcast:10.0.7.255  Mask:255.255.248.0
              inet6 addr: fe80::230:1bff:fea0:97b0/64 Scope:Link
              UP BROADCAST RUNNING MULTICAST  MTU:1500  Metric:1
              RX packets:449598328 errors:0 dropped:22 overruns:0 frame:0
              TX packets:361333927 errors:0 dropped:0 overruns:0 carrier:0
              collisions:0 txqueuelen:1000 
              RX bytes:4035468488 (3.7 GB)  TX bytes:1736453555 (1.6 GB)
              Interrupt:17 
    
    lo        Link encap:Local Loopback  
              inet addr:127.0.0.1  Mask:255.0.0.0
              inet6 addr: ::1/128 Scope:Host
              UP LOOPBACK RUNNING  MTU:16436  Metric:1
              RX packets:240354428 errors:0 dropped:0 overruns:0 frame:0
              TX packets:240354428 errors:0 dropped:0 overruns:0 carrier:0
              collisions:0 txqueuelen:0 
              RX bytes:959731648 (915.2 MB)  TX bytes:959731648 (915.2 MB)

This above computer has two Ethernet interfaces : eth0 and eth1 and lo. lo is a virtual loop-back device, ignore it.

At this point you might be trial and error to figure which Ethernet interface to use. However, there is another trick that may help. Usually, when an Ethernet port becomes connect or disconnected, a kernel message is generated. Try disconnecting/reconnecting an Ethernet port and then look at the end of the kernal log messages to determine which port was connected/disconnected.

  • dmesg

The above command will produce a lot of output, but you probably only care about the stuff that occurred near or at the end.

  • ...
    ...
    [4432553.221845] sky2 eth1: Link is down.
    [4432556.005255] sky2 eth1: Link is up at 1000 Mbps, full duplex, flow control both

As you can see, eth1 was just disconnected and reconnected.

Run pr2_etherCAT

If it is not already running, start the ROS core in a new terminal.

  • roscore

pr2_etherCAT needs to be run with root permissions. Using sudo doesn't work because pr2_etherCAT can't find the necessary linked libraries. There are a couple ways to run with extra privileges:

  1. Use pr2-grant
  2. Run pr2_etherCAT as root

pr2-grant

pr2-grant is similar to sudo in that it provides special privileges to some other program. Unlike sudo, pr2-grant will not mess up the library path that ROS uses. Unfortunately, you need to compile and setup pr2-grant yourself.

Get libcap:

  • sudo apt-get install libcap-dev

Checkout,compile,pr2-grant:

  • svn co https://code.ros.org/svn/pr2debs/trunk/packages/pr2/pr2-grant
    cd pr2-grant
    make

Install pr2-grant. pr2-grant needs to be owned by root and have the suid bit set. It is also the most convenient when put on the system path.

  • sudo cp pr2-grant /usr/local/bin
    sudo chown root:root /usr/local/bin/pr2-grant
    sudo chmod +s /usr/local/bin/pr2-grant

Running pr2-etherCAT using pr2-grant:

  • roscd pr2_etherCAT
    pr2-grant ./pr2-etherCAT -ieth0 -x ~/robot.xml

run as root

Running pr2_etherCAT as root is less preferable to using pr2-grant. bash as root and re-source the ROS setup script before running pr2_etherCAT.

  • sudo bash 
    <<<type in password>>>
    source ~/ros/setup.sh
    rosrun pr2_etherCAT pr2_etherCAT -i eth0 -x ~/robot.xml

pr2_etherCAT arguments

  • pr2_etherCAT pr2_etherCAT -i eth0 -x ~/robot.xml

Here is a quick breakdown of the arguments given to pr2_etherCAT:

  • -i eth0 : EtherCAT devices are connected to network interface eth0. This will be different for a different computer.

  • -x ~/robot.xml : Use the file robot.xml as the robot description. This file was created in a previous stop

If the minimal robot description was used, a some warning messages will be generated.

  • [ WARN] [1272079077.138525407]: No transmissions were specified in the robot description.
    [ WARN] [1272079077.138608160]: None of the joints in the robot description matches up to a motor. The robot is uncontrollable.

Looking at Diagnostics

pr2_etherCAT publishes a lot of information to the diagnostic topic. Looking at the diagnostics output is an easy way so see pr2_etherCAT working. The runtime_monitior provides an easy way to watch data on the /diagnostics topic.

Get runtime_monitor package from diagnostics_monitors :

On ROS Electric:

  • sudo apt-get install ros-electric-diagnostics-monitors

On ROS Fuerte:

  • sudo apt-get install ros-fuerte-diagnostics-monitors

Run:

  • rosrun runtime_monitor monitor

You should see a that looks something like:

  • Screenshot-Runtime Monitor.png

In the above screen-shot there are three different diagnostics sub-topics:

  • EtherCAT Device (bl_caster_l_wheel_motor)
  • EtherCAT Master
  • Realtime Control Loop

All three of these topics are produced by pr2_etherCAT. When a sub-topic is selected on the left side of the window, its diagnostic output is shown on the right side.

For more information on diagnostics look at diagnostics.

Troubleshooting

Wiki: pr2_etherCAT/Tutorials/Running (last edited 2012-09-07 20:33:16 by dking)