Skip to content

Instantly share code, notes, and snippets.

@hmartiro
Last active May 29, 2019 13:49
Show Gist options
  • Star 4 You must be signed in to star a gist
  • Fork 1 You must be signed in to fork a gist
  • Save hmartiro/07874f18834d20b38cf8 to your computer and use it in GitHub Desktop.
Save hmartiro/07874f18834d20b38cf8 to your computer and use it in GitHub Desktop.
How to drive Barrett Tech robots from stock Ubuntu

This document describes how to communicate with and control robotic products from Barrett Technologies, such as the WAM Arm and BarrettHand, from a computer running stock Ubuntu. In particular, it describes how to achieve good performance without being restricted to Xenomai, the real-time framework supported by Barrett.

Disclaimer: Running in non-realtime by definition gives no hard guarantees. While this method has supported robust torque control in operational space, please do not implement it on your production baby-feeding robot and then blame me.

Ingredients:

  • Barrett Tech product
  • Computer running Ubuntu >= 12.04
  • CAN hardware (for example, USB or PCI cards from PEAK)

Install Dependencies

Install build tools:

sudo apt-get install build-essential git-core cmake cmake-curses-gui

Install required libraries and headers:

sudo apt-get install libeigen2-dev libgsl0-dev libncurses5-dev libboost-dev
sudo apt-get install libboost-thread-dev libboost-system-dev libboost-python-dev

Install a newer version of libconfig++ than is available in the 12.04 repos, and that has a public getCSettings method as required by libbarrett:

wget http://web.barrett.com/svn/libbarrett/dependencies/libconfig-1.4.5-PATCHED.tar.gz
tar xzf libconfig-1.4.5-PATCHED.tar.gz
cd libconfig-1.4.5
./configure
make && sudo make install

If you are on 14.04 or higher, you can choose to install libconfig++-dev from the repo and manually add this method to /usr/include/libconfig.h++:

// BARRETT(DC): Added this inline method to allow simultaneous libconfig and
//              libconfig++ use.
config_setting_t *getCSetting() const { return(_setting); }

Build the driver

Clone the libbarrett library:

git clone https://github.com/BarrettTechnology/libbarrett

Set up CMake build:

cd libbarrett
mkdir build && cd build
cmake ..

If this didn't spit out any errors other than "xenomai NOT found", then CMake is finding all of the dependencies correctly. Now, configure some options using ccmake:

ccmake ..

Using the arrow keys and enter, set NON_REALTIME and OPTIMIZE_FOR_PROCESSOR to ON. If you don't want to clog up your home directory, change EXAMPLES_DIR and SANDBOX_DIR. Press c, then c, then g to configure and generate. Then, try to build:

cmake ..
make && sudo make install

If this succeeds, you should have libbarrett.so on your path! Check with whereis libbarrett. You should also be able to build your examples:

cd /my/dir/to/libbarrett_examples
mkdir build && cd build
cmake .. && make

Try running ./ex01_initialize_wam if you have a WAM - if you get an exception stating CANSocket::open(): Could not open CAN port, you are in the right place.

Set up CAN

At this point, the last setup step is to enable CAN communication between the computer and the robot. When building for Xenomai, libbarrett uses rtcan. When building non-realtime, libbarrett uses SocketCAN.

SocketCAN is the official CAN driver for Linux and comes with the kernel. You may need to poke these kernel modules:

sudo modprobe can
sudo modprobe can_raw

You will need a compatible CAN adapter if your computer doesn't come with CAN ports. There are many CAN-to-USB dongles or CAN-to-PCI cards out there. Barrett likes the ones from PEAK.Connect the adapter and plug in the CAN cable from your robot.

Type dmesg, and you should see some log messages telling you what network interface was connected. It will usually be can0 or can1. If there was an error, you may need to go to the vendor website and install their driver. The instructions from here on may be specific to the PEAK cards (drivers here).

Bring up this interface and extend its queue length (I'll assume can0):

sudo ip link set can0 up
sudo ifconfig can0 txqueuelen 10000

To check if this worked, type ifconfig. You should see the can0 interface with the specified queue length. Finally, we need to change the bitrate from the default 500KB to 1M.

sudo nano /etc/modprobe.d/pcan.conf

Set the bitrate to 1M (0x0014):

# pcan - automatic made entry, begin --------
# if required add options and remove comment
# options pcan type=isa,sp
options pcan bitrate=0x0014
install pcan /sbin/modprobe --ignore-install pcan
# pcan - automatic made entry, end ----------

Check the CAN settings using cat /proc/pcan. You should see your interface with a -btr- of 0x0014 and all zeros for -errors-. If the bitrate is not set, try restarting and re-bringing up the interface. If there is some other error, consult the driver manuals.

Finally, we need to tell Barrett to use the interface that we just set up. Open up /etc/barrett/default.conf and set port equal to the number of your CAN interface, so 0 for can0 and 1 for can1.

Run the example

Power on the robot and run ./ex01_initialize_wam or whatever example is relevant. If it works, congrats! You are controlling your robot from stock Ubuntu. You can try some more interesting examples or start writing your own programs. Either way, skip the rest of this section and move on to the next.

If it didn't work, take a look at the system log, which libbarrett writes to. Try opening a new terminal window, run tail -f /var/log/syslog, and re-run the example. can-utils provides debug tools for SocketCAN and may be useful if you know what you're doing.

If you get an error saying No SafetyModule was found, that means libbarrett is trying to communicate with the robot but is not receiving a reply. Make sure the robot is on, the right cable is plugged in, the port is correct, and the bitrate is correct.

Real-time scheduling

You can now control your robot from a computer running stock Ubuntu. You can start writing up your application using the examples as guides. However, this is not the best we can do. We can go from delays in the range of tens of milliseconds to tens of microseconds.

Short Version: Run sudo chrt -rr 90 ./my-program instead of ./my-program, and your delay/jitter will go down by orders of magnitude.

Long Version:

Let's say you run your program, which reads joint positions/velocities and commands torques to the robot. Your program runs as one or multiple threads, which are scheduled and executed in time slices by the kernel scheduler. What this means is that the timing of your commands depends on when the scheduler decides to let your thread run. If you have ten Java update processes running, your torque controller may have to wait a very long time (tens of milliseconds) to run. This unpredictable delay and jitter can easily cause horrible performance problems. We can hint to the scheduler that our process is important using nice with its priority rankings of -20 to 20, but this doesn't have a large effect.

Lucky for us, some real-time scheduling features based on the RT patch have been added to the stock kernel. Using the sched_setscheduler system call, we can set a process to have various scheduling policies, and a few of them are "real-time". Real-time policies have their own priority level of 1-99, but are all strictly higher priority than non-realtime processes. In top or htop, they show priority 'rt'. In particular, if SCHED_FIFO is given to a process where it is the only one in that priority, that process (and children) cannot be pre-empted by any other process unless it explicitly calls a yield function. In fact, a process running a while loop with SCHED_FIFO in a single-core system would take over the processor and crash the computer because it is impossible for any other thread to preempt it.

What this means is that if we run our program as a real-time process using SCHED_FIFO or SCHED_RR, it will be able to preempt other processes at any time other than during system calls. This represents a drastic improvement in performance by cutting down jitter and delays by orders of magnitude (often in the range of 5-40 microseconds). Running a process in this way makes a huge difference in performance, and actually comes quite close to real-time. In practice, it is usually easier to use the chrt command to invoke the program than use the system calls. For example:

sudo chrt -rr 90 ./ex04_display_basic_info

This will run example 4 with the round-robin real-time scheduler (SCHED_RR) with priority 90. The priority level usually doesn't matter, because it is only compared other real-time processes. If you are running multiple real-time processes, then you may want to think about this. If you are launching many threads, it is probably a bad idea to use chrt and you should specifically make the important ones real-time using the system calls.

This will probably be good enough for any use. However, it is important to note again that the real-time thread can preempt any non-realtime thread except during a system call. In my experience, this has meant occasional delays in the range of 200 microseconds. This is very little compared to the 850 microseconds it takes to send torque commands or read sensor data across the CAN bus. However, if some other process were to be in the middle of allocating gigabytes of memory, it might be a significant delay before the real-time process can preempt it. The RT patch fixes this by making system calls preemptible. In fact, it's possible that the only performance boost using the RT patch will introduce is to eliminate these spikes. It has not been tested, but using this method with the RT patch should work perfectly well.

One final hack on a stock kernel is to make your real-time process busy-wait instead of sleeping. This way, no other process will ever run on the core and there will be no spikes at all. However, this is terrible real-time design and is NOT recommended, because this process will use 100% CPU. On a single-core system, this can prevent everything from running and force a reboot. There is an emergency measure to prevent this, but it may or may not be enabled. Use real-time scheduling with caution - don't sprinkle it on everything.

If your controller depends on multiple processes, make sure to run them all in real-time or it will be pointless. I suggest using the htop tool to see which processes are real-time and how much CPU they are using.

Note about libbarrett frequency

The libbarrett library by default runs at 500Hz. Somewhere in the documentation, they note that they support operation up to 1000Hz. I haven't found an API call that changes this, so I recompiled libbarrett with DEFAULT_LOOP_PERIOD set to 0.001 instead of 0.002 in include/barrett/products/product_manager.h. Things still worked, but I haven't tested if performance is actually better. The performance limitation may be the speed of the CAN bus rather than the loop period.

Redis Driver

I've created a Redis pubsub based driver for the 7DOF Barrett WAM. It is a process that receives actuator commands and sends sensor data over Redis pubsub. This enables inter-process or inter-computer controllers, where the controller just sends and receives messages to a Redis server. It's been demonstrated to achieve robust torque control in operational space between two computers on a local ethernet network. It also creates nice separation of concerns, because the computer or process running the controller doesn't have to worry about any of this setup or interacting with the robot itself. Users can type commands or get sensor data straight from a Redis console.

It is located here, and uses Redox, my asynchronous C++ client for Redis. Currently, the driver has no setup instructions so it will be hard to get going. This is a TODO, but in the meantime you can contact me if you're interested in using it. In particular, I had to adapt the headers for libbarrett for C++11 by changing all static const double variable declarations to static constexpr double.

Resources

Some useful links:

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment