Professional and hobbyist roboticists alike are snapping up Robotis Dynamixel Servos. These "smart" servos serve an important niche between $30 hobby servos and super-expensive harmonic drive servos. They sport torques ranging from 12 kg·cm to 106 kg·cm, and even more when doubled-up. Most of my experience is with the RX-28 and RX-64 variants, which have 300° swing, 10-bit position sensing resolution, (roughly) 8-bit position control, force/torque sensing, available compliance mode, and can daisy-chain more than 250 servos. At Georgia Tech's Healthcare Robotics Lab, we use dozens of these servos. I recently invested a decent amount of time overhauling our open-source (Python) control software, adding (among other things) thread-safe operation and ROS (Robot Operating System) compatibility. In this post, I'll do a brief overview of the Robotis Dynamixel offerings, look at a number of impressive applications where they are utilized, share pictures of a servo's disassembly, and give a brief tutorial using the new (awesome) open-source software libraries.
Robotis offers a number of servos, a few of which are summarized below. I believe all four profiled below are also capable of continuous turn operation.
AX-12 Servo |
RX-28 Servo |
RX-64 Servo |
EX-106 Servo |
|
| Torque@Voltage: |
12 kg·cm @ 7V |
28 kg·cm @ 12V |
64 kg·cm @ 18V |
106 kg·cm @ 18.5V |
| No-Load Speed: | 0.269sec / 60° |
0.167sec / 60° | 0.162sec / 60° |
0.143sec / 60° |
| Angular Res.: |
0.35° | 0.29° |
0.29° |
0.07° |
| Servo Mass: | 55g | 72g | 125g | 155g |
| Operating Angle: | 300° | 300° | 300° | 360° |
| Max Current: |
900mA | 1200mA | 1200mA | 3200mA |
| Motor Type: |
Cored motor | Maxon RE-MAX |
Maxon RE-MAX | Maxon RE-MAX |
| Gear Type: |
Plastic gears | Metal gears | Metal gears | Metal gears |
| Approx.Cost: | $45 ea. |
$200 ea. |
$280 ea. |
$500 ea. |
| Datasheet: |
The thing that makes these servos really stand out is their modular nature. There are numerous brackets available to fit the mounting holes on the servos; thus, giving you maximum flexibility to let you build your own robot mash-ups. Oh, and for those applications where you really need some torque, you can double-up the servos. For example, the Double EX-106 shown below right can output 210 kg·cm of torque -- that's definitely in the realm severe finger-pinching.
The servos operate over serial protocols (TTL RS232 for the AX-12, RS485 for the others). Personally, I prefer to use the Robotis USB2Dynamixel adaptor pictured below. Communications go over USB; power is connected externally. The same communications / power lines can operate over 200 servos.
This is just a small sampling of projects that use Robotis servos. Know of any others? Leave pointers in the comments.
|
This is the Giger robot from Trossen Robotics. Among hobby humanoids, Giger reigns supreme. It has 10 x EX-106s, 6 x RX-64s, and 8 x RX-28s for 24 total degrees of freedom (DoF). |
![]() |
This Robotis-powered arm / hand combination also comes from the folks at Trossen Robotics. Depending on how well compliance mode functions (I've yet to experiment), I imagine an arm and gripper like this (with position control, torque sensing, and some compliance) could be quite useful. More importantly, it costs a fraction of advanced full-scale arms. |
![]() |
In fact, Crustcrawler sells kits to build your own Robotis arms and hands. Note the doubling up of servos for added torque in the lower joints. |
|
No discussion of Robotis products would be complete without mention of the Bioloids robot kits. These kits are like a high-tech version of Lego Mindstorms -- you can build pretty much anything using Robotis AX-12 servos. |
![]() |
In the Healthcare Robotics Lab (to which I belong), we use these servos extensively to construct camera and RFID pan-tilt units. We also use these servos to build tilting laser rangefinders that produce dense point clouds of the environment. The Robotis servos give fast enough angular readings (at sufficient resolution) to quickly build scans with more than 60,000 points. A tilting laser rangefinder and resulting point cloud are shown. The designs have been released as open-hardware. |
I've taken apart many servos in my time, usually to hack them for continuous rotation (aka, turn them into cheap gear motors). Wanting to know what made the Robotis servos so special, I decided to (non-destructively) open up a spare RX-64 we had lying around. I would like to share photos of their internals. For the disassembly, the front (side with the output shaft) had the servo horn removed first. The servo under inspection is shown:
Getting to the internals is quite simple -- just remove four screws on the back. Like most servos, there is a printed circuit board (PCB) with electronics connected to a motor (in this case, a nice Maxon RE-MAX motor) and a potentiometer (variable resistor) for position feedback. Unlike a traditional servo, the circuitry is a bit more involved. On top of the PCB, power conditioning components (such as capacitors) are visible. The large chip on top appears to be a PowerSO20 packaged H-Bridge, such as the STmicro L298. On the bottom of the PCB, there is a Atmega8 microcontroller (16AU to be precise) with 16 MHz oscillator that is the "brains" of the device. The blue component is a potentiometer (variable resistor) that is coupled to the servo's output shaft via a plastic rod coming up through the servo body. This component provides position feedback of the output shaft. All-in-all, pretty elementary stuff -- no big mystery here, though it is nice to see an Atmega chip (I use them frequently for projects of my own).
Inside the front cover are the metal gears (said to have a 1/200 reduction ratio). On the left, they are removed. On the right, they are assembled. You can see how the output shaft / gear is also connected to the plastic rod extending to the PCB's potentiometer. Again, nothing earth-shattering; however, the mechanical design is very solid.
Restoring (and re-certifying) the servo was also straight forward. No harm, no foul.
As I mentioned earlier, I recently invested a decent amount of time overhauling my lab's open-source Robotis servo control software. The code is written entirely in Python and is thread-safe, so that multiple servo objects can be controlled / queried "simultaneously" on the same USB2Dynamixel bus (within the same process). The library should function on Linux, Mac, and Windows (yay, python!), and the only dependency is PySerial for communications. The code has only been tested on the RX-28 and RX-64 variants, as these are the only ones I possess. Naturally, I provide no warranties about its use (see disclaimer in the source), and I cannot speak to its compatibility with the other Robotis servos variants.
I have included the stand-alone library here: lib_robotis.py (the filetype should be saved as .py). "Official" versions can be found in the Healthcare Robotics Lab Google Code repository. Now, on to a quick demonstration...
After first hooking up the servo plus USB2Dynamixel system, you'll want to find out which ID's are present. By default, the Robotis servos have an ID of 1, so you'll need to change them one at a time. Let's assume your USB2Dynamixel is present as '/dev/ttyUSB0' on a Linux machine (Note for Windows users: this will just be the COM port number, such as '1'). From the command line:
$ python lib_robotis.py -d /dev/ttyUSB0 --scan
Scanning for Servos.
FOUND A SERVO @ ID 1
From IPython (or any python shell), we can change the ID to one of our choosing (say, 11):
from lib_robotis import *
dyn = USB2Dynamixel_Device('/dev/ttyUSB0')
p = Robotis_Servo( dyn, 1 )
p.write_id( 11 )
By default, a number of options are automatically set in lib_robotis.py to specify the home encoder position (that which corresponds to an angle of 0 degrees), minimum and maximum safe angles, maximum speed, etc.:
defaults = {
'home_encoder': 0x200,
'rad_per_enc': math.radians(300.0) / 1024.0,
'max_ang': math.radians(148),
'min_ang': math.radians(-148),
'flipped': False,
'max_speed': math.radians(50)
}
If you want to override these options simply store an entry in a configuration file (servo_config.py) in the same directory as the library. You can specify any or all of the options on a servo-by-servo basis, as shown:
import math
servo_param = {
# Pan Servo
11: {
'home_encoder': 430,
'max_ang': math.radians( 141.0 ),
'min_ang': math.radians( -31.0 )
},
# Tilt Servo
12: {
'home_encoder': 507,
'max_ang': math.radians( 46.0 ),
'min_ang': math.radians( -36.0 )
}
}
Now, I have two Robotis servos configured with defined "home" angles and have safety limits placed on them (for example, to prevent accidentally commanding angles that would result in collisions). Moving the servos around is a simple matter of code. You can have the movements be blocking (waits for one servo's movement to finish before allowing another command) or non-blocking, so that both servos can move simultaneously (as is the case below):
from lib_robotis import *
dyn = USB2Dynamixel_Device('/dev/ttyUSB0')
p = Robotis_Servo( dyn, 11 )
t = Robotis_Servo( dyn, 12 )
t.move_angle( math.radians( 10 ), blocking = False )
p.move_angle( math.radians( 10 ), blocking = False )
A whole slew of useful commands are already implemented, such as:
disable_torque(self)
enable_torque(self)
is_moving(self)
returns True if servo is moving.
move_angle(self, ang, angvel=None, blocking=True)
move to angle (radians)
move_to_encoder(self, n)
move to encoder position n
read_angle(self)
returns the current servo angle (radians)
read_encoder(self)
returns position in encoder ticks
read_load(self)
number proportional to the torque applied by the servo.
sign etc. might vary with how the servo is mounted.
read_temperature(self)
returns the temperature (Celsius)
read_voltage(self)
returns voltage (Volts)
write_id(self, id)
changes the servo id
In addition, functions like "read_address" and "write_address" give the ability to experiment with all other modes and registers in the servo.
I mentioned that I also added ROS (Robot Operating System) compatibility. A ROS ecosystem is required, so it doesn't make sense to hand out individual files. If you want the ROS bindings, they can be found in the Healthcare Robotics Lab Google Code repository. Essentially, ROS permits multi-process operation, such as data streaming or control by local or remote (via TCP/IP) computers. The details of ROS are beyond the scope of this article, so I'll refer interested parties to their website. Regardless, here is a simple ROS server that constantly broadcasts the pan-tilt angles and allows them to be changed by any local or remote computer.
import roslib
roslib.load_manifest('robotis')
import rospy
import robotis.lib_robotis as rs
print 'Sample Server: '
# Important note: You cannot (!) use the same device in another
# process. The device is only "thread-safe" within the same process
# (i.e. between servos (and callbacks) instantiated within that
# process)
dev_name = '/dev/ttyUSB0'
ids = [11, 12]
names = ['pan', 'tilt']
dyn = rs.USB2Dynamixel_Device( dev_name )
servos = [ rs.Robotis_Servo( dyn, i ) for i in ids ]
ros_servers = [ ROS_Robotis_Server( s, n ) for s,n in zip( servos, names ) ]
try:
while not rospy.is_shutdown():
[ s.update_server() for s in ros_servers ]
time.sleep(0.001)
except:
pass
Now, multiple processes (locally or remotely) can interact with the servos. Two could be monitoring the angles:
$ rostopic echo /robotis/servo_tilt
$ rostopic echo /robotis/servo_pan
Another could be watching to see if they are moving:
from ros_robotis import *
pan = ROS_Robotis_Client( 'pan' )
tilt = ROS_Robotis_Client( 'tilt' )
while True:
print pan.is_moving(), tilt.is_moving()
And two others could be changing the angles!
from ros_robotis import *
import math
tilt = ROS_Robotis_Client( 'tilt' )
tilt.move_angle( math.radians(0), math.radians(10), blocking=False)
from ros_robotis import *
import math
pan = ROS_Robotis_Client( 'pan' )
pan.move_angle( math.radians(0), math.radians(10), blocking=False)
I guess that pretty much wraps up my examination of Robotis Dynamixel servos. I'd be interested to hear your thoughts and experiences (like how well compliance mode works) in the comments.
Comments
10:21 pm
Hi,
Firstly,thanks for your article.
But about double EX-106,one question about double output torque?This is a smart mechanical design,but how control those Dynamixels at the same time?
4:43 pm
@Meredith,
I have no experience with a single (let alone double) EX-106. However, I can speculate...
Some quick experiments seem to indicate that I can send / receive commands every 16ms. Assuming you do not specify outrageous angular velocities, you should have ample time to command both servos' angles, effectively doubling-up the total torque.
I imagine it is important to prevent the motors from "fighting" with each other. This probably means being careful when setting the home encoder position, and may benefit by setting one of the servo's compliance margin / slope (see datasheet).
1:28 am
I'm honored -- it looks like the folks at ROS.org like this article.
3:22 am
@Travis:
The EX-106 supports a "dual mode" where 2 servos are directly connected via a synchronization cable, so one only needs to send the master servo commands (see page 33 of the EX-106 manual). This configuration will probably be used on some robots in this year´s RoboCup Humanoid AdultSize league competition.
The RoboCup 2009 Humanoid League KidSize winners featuring RX-28 and RX-64 can be seen here btw :) http://www.youtube.com/user/DarmstadtDribblers
2:23 am
@ Stefan,
Thanks for the clarification. I've never used the EX-106, let alone dual-mode. However, having a separate mode makes a lot of sense (avoids some of the complications I mentioned). More than anything, it serves me right for not referring to the datasheet; it has been a long time since someone told me to RTFM ;-)
4:31 pm
7:48 pm
@ Mirko,
There is a compliance mode which might be able to apply some sort of rudimentary impedance control (a virtual spring). I'm referring to compliance margin, compliance slope, and punch (addresses 0x1A-0x1D for the RX28's, see instruction manual).
Unfortunately, I haven't played with the compliance parameters, so anything I say is purely speculative. Perhaps you could command an angle far from the current one, set a compliance slope of zero, and nonzero punch to get constant torque...?
Let me know what you find out!
9:47 am
@ Travis
Thanks for your hints, and sorry for answering so late, I haven't had the opportunity to look at the forum.. I found an interesting work by a Portughese research group, which states that it is possible to relate the desired torque to the angular speed, and then (in free run mode, that is goal position set to zero) use the angular velocity input control to indirectly imposing the reference. The relation is nonlinear, because of static friction at low speeds. You can find more infos at http://humanoids.dem.ist.utl.pt/.
Thanks again
12:00 am
You should mention to readers that according to the manufacturer's comment, the Torque or Load measurements in Dynamixel motors are not actual measurements, they are simply based on the difference between current position and the goal position! And to make it worse, the readings only change 7 times per second, and are very innacurate!
This means Dynamixel motors are great if you need servo motors that are strong & modular, but the motors cant be used for complicated feedback systems like Torque Control or even Current Control. (More details can be found here: "http://www.shervinemami.co.cc/dynamixels.html")
Cheers,
Shervin.
3:14 pm
4:18 pm
Hi, I am using your operating scheme "lib_robotis" to communicate with the USB2Dynamixel controller. However I keep getting the "Access is Denied" error that plagues serial communication ports. Any suggestions? I run Windows XP if that helps.
3:22 pm
With Brian's help, we determined that the "Access Denied" is a weird, known WinXP-only "bug" in pyserial with a relatively simple work-around. The lib_robotis library has been updated both on Hizook and in the Google Code repository.
Post new comment