Robotis Dynamixel Servos: Overview, Applications, Tear-Down, and Open-Source Software

Robotis Dynamixel RX-28 Smart Servo

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.

 

Overview of Robotis Servo Offerings: 

 

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
 

AX-12 Robotis Servo

RX-28 Robotis Servo

RX-64 Robotis Servo

EX-106 Robotis 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°  280°
 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:  PDF  PDF  PDF  PDF

 

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.

Robotis Servo Bracket  Robotis Servo Bracket  Robotis Servo Bracket  Double EX-106 Robotis Servos

 

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.

Robotis USB2Dynamixel

 

Robotis Servo Applications: 

 

This is just a small sampling of projects that use Robotis servos.  Know of any others?  Leave pointers in the comments.

Giger Robot from Trossen Robotics
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).
 Robotis Servo Arm and Hand from Trossen Robotics 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.
 Crustcrawler Robotis Servo Arm and Hand 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.
Bioloids Robot Kit
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.
 Tilting Laser Rangefinder using Robotis Servo and Hokuyo UTM 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.

 

Disassembling a Robotis Servo: 

 

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:

Robotis RX-64 Servo Front   Robotis RX-64 Servo Back

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

Robotis RX-64 Internals: Inside the back cover  Robotis RX-64 Internals: Inside the back cover, under PCB  Robotis RX-64 Internals: Inside the back cover, under PCB

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.

Robotis RX-64 Internals: Inside the front cover     Robotis RX-64 Internals: Inside the front cover

Restoring (and re-certifying) the servo was also straight forward.  No harm, no foul. 


Open-Source Robotis Servo Software Library and Tutorial: 

 

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 servo angles to be changed by any local or remote computer.

import roslib
roslib.load_manifest('robotis')
import rospy
 
from robotis.ros_robotis import *
 
poller = ROS_Robotis_Poller( '/dev/ttyUSB0', [11,12], ['pan', 'tilt'] )
rospy.spin()
poller.stop() 
 

 

Expanded out, the poller is essentially performing the following inside a thread:


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

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?

—Meredith

@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).

 

—Travis Deyle

I'm honored -- it looks like the folks at ROS.org like this article. 

—Travis Deyle

@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

@ 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 ;-)   

—Travis Deyle
Hi, I'm just starting using the Bioloid kit, so maybe this is a silly question.  I have noticed that the documentation doesn't seem to mention the possibility to have a Dynamixel servo directly torque controlled, as I wished. Do you think it's possible? Thanks
—Mirko

@ 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!

 

—Travis Deyle

@ 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

—Mirko

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 you can query the current servo position at high temporal resolution (AFAIK as fast as the bus will allow), and the position encoder is also quite accurate.  Since it is running a form of proportional control, the difference between the current position and the target position will be proportional to the motor torque being applied.  The downside is that this is the applied torque at the motor, which is behind a bunch of gears, so it's still not very sensitive to forces on the shaft.
—Ethan

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.

—Brian

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.

—Travis Deyle

Hello,

We're interested in the concept of using the tilting hokuyo. However we were wondering, since both devices are not realtime, how do you synchronise the data? The scans come in every 25 milisecond, how do you get the exact angle of the dynamixel at that time?

Second question: Do you use position control or speed control on the dynamixel. I can image the whole systems runs much smoother with a  constant velocity than jumping from position to position.

Thanks, 

—Tim Clephas

@ Tim,

The original tilting Hokuyo code didn't worry much about the timing; it would read the servo angle whenever a scan arrived to assemble the scan.  This meant that the angles weren't always that precise, but the scans were "good enough".

If I were making a tilting Hokuyo now, I would use ROS's tf package to handle timing: the messages (angles and scans) would each be given a timestamp by ROS and tf would actually interpolate the transformations when assembling the scans.  This is a process I frequently use with my ROSified Robotis Servos.  The tf interpolation is (roughly) linear, so that when a new scan arrives half-way between two successive angle pollings, the scan is transformed using the intermediate angle -- this means you can actually have higher angular resolution than provided by the Robotis Servo alone.   Given that ROS supports both the Robotis Servos (see post above) and Hokuyo laser rangefinders "out of the box," it really isn't too bad to set up.

As for position / speed control, when you issue a command to the Robotis Servo using the move_angle command, you specify an angular velocity as well.  It does a pretty good job of moving at a constant velocity, as long as there aren't any major load discontinuities.

—Travis Deyle

@ Travis

 Thanks for the very fast response! 

I think the use of the tf package is a good idea. I don't have a dynamixel yet, but am I correct in the following situation?

Send the dynamixel to a position of 60° with a speed of lets say 60º per second, then the dynamixel will fullfill a complete scan with a constant velocity.

Ros just keeps polling the scans and the position of the dynamixel, attach a timestamp and combine the signals later. I think, since I only have to poll the position, this could be done every 10 ms orso¹?

Thanks, 

¹http://www.shervinemami.co.cc/dynamixels.html 

—Tim Clephas

@ Tim,

Your understanding is correct, though obviously the velocity won't be "constant" for such a fast, short movement.   Our movements usually take around 5 seconds to get good, dense scans with accurate interpolated transforms.

If you use the ROS package I provided, the "poller" class will allow you to send in new target angles via a ROS service, and then the poller will make the read angle queries as fast as possible.  You will need another ROS node that subscribes to these angle topics and publishes the tf transforms (let me know if you want the code I use...).  Using default settings (and accounting for Python, USB2Dynamixel, and code overhead) the Robotis Servo package updates angles at about 30Hz (33ms).

When you go buy your Robotis Servo, you might consider buying them from this link -- it really helps out Hizook

—Travis Deyle

Here's a patch to add support for the AX-12 dynamixel servos (they need a baudrate of 38400).

397a398,399
>     p.add_option('--baud', action='store', type='int', dest='baud',
>                  help='baudrate of USB2Dynamixel connection [default=57600]', default=57600)
405c407
<     dyn = USB2Dynamixel_Device(opt.dev_name)
---
>     dyn = USB2Dynamixel_Device(opt.dev_name, opt.baud)

Jared

@Jared: Thanks for the patch. It has been integrated into the gt-ros-pkg code repository.

—Travis Deyle

Hi,

in the datasheet on your page I found that the max. current of the EX-106 is 3.2A,  but on the robotis Page I found that it is 7A.

What is the right value?

And one more question: Maybe you know, how the current of the ex-106 is pulsed or not. When pulsed: how high is the maximum Pule? In which frequency is it pulsed?

Thank you in advance for your answer!

—Yaroslav

@Yaroslav,

You're right, the online spec sheet (here) does say that the stall torque is  107kgf.cm (at 18.5V, 7A).  I'm not sure why they went away from (versioned) PDF datasheets, but I would probably trust their online documentation to be the most up to date.

I am pretty sure that they control the motor current using pulse width modulation.  Unfortunately, I do not know what frequency they're using for the PWM.  Also, I assume that they have sufficient onboard filtering (capacitive storage) to handle the current pulses -- and that the end-user designs can just worry about the average current.  Of course, both of these questions could be answered by popping the case off an EX-106 and using an oscilloscope for testing.  Unfortunately, I do not have and EX-106 laying around, nor can I spare the cycles to measure those parameters on an RX-28 (and I'm not sure if that would help anyway -- I believe the EX-106 might have different internals). 

I suppose that's all-together unhelpful... sorry.  Wish I knew more.

—Travis Deyle
I'm curious about the geartrain backlash.  Is the final splined output shaft free from noticeable backlash?
DJ
I have been using the Rx-28 for the development of a 3 degree of freedom 6 legged walker and they keep on overheating! We are never close to the maximum operating torque. What is the solution? How can we spend so much money on a motor that cannot operate for more then a few seconds at less then 80% mazimum torque?
—Anonymous

@Anonymous: Are you sure this is an overheating issue?  Have you verified the opcode returned from the motors when they shut down?

The reason I ask... At static loads approaching 80% of the maximum rated torque, you're likely experiencing dynamic torques far exceeding the limits -- this causes the motors to self-shutdown.   My wife used to work in electromechanical automation... they always specced motors that were 2-3 times the rated (static) load for precisely this reason.   

—Travis Deyle

Travis: Great post!

I tested this on my linux (Mint 12) computer running python 2.7 and connecting to a single AX-12+ servo. I noticed that when reading the reply (through receive_reply()), there was a zero character '(\x00') before the two \ff characters. I modified the function to read and discard this, which fixed the problem.

Is this issue specific for my hardware/software or have you seen it before?

—Kjartan H

@Kjartan,

No, the 0x00 byte at the beginning of the response packet is not normal.  According to the Robotis communication protocol, the response packet should start with two 0xFF bytes:

http://support.robotis.com/en/product/dynamixel/communication/dxl_packet.htm

This really shouldn't have anything to do with python 2.7, as many others (myself included) now use that version.  My best guess: 0x00 at the start of a receive looks like a "start byte" or something wonky with your USB-to-RS485 converter.  Which USB converter are you using?  

—Travis Deyle

@Travis

thanks a lot for your quick response!

My guess is the same as yours, since the robotis documentation is quite clear about the byte sequence.

I am using the USB2Dynamixel gadget. I have tried the SDK from robotis compiled with gcc, and it worked "straight out of the box". I looked at the code in the SDK (dynamixel.c), and it has a more pragmatic algorithm for finding the header:

// Find packet header
for( i=0; i<(gbRxGetLength-1); i++ )
{
   if( gbStatusPacket[i] == 0xff && gbStatusPacket[i+1] == 0xff )
   {
      break;
   }
   else if( i == gbRxGetLength-2 && gbStatusPacket[gbRxGetLength-1] == 0xff )
   {
      break;
   }
}

 

To test this I added the following line

printf("First byte in gbStatusPacket: %d\n", gbStatusPacket[0]);

 

recompiled, and sure enough, it is zero.

Maybe you want to patch your python code to allow for an unknown sequence of bytes before the \xff\xff pair?

—Kjartan H

Hello,

Will this code work only with the USB2Dynamixel or is it compatible with Robotis CM700 as well? Or is there any other way to control the dynamixels with a CM700 controller from ROS?

Thanks,

—SSR

@SSR,

Wow, I didn't even know about the CM-700 controller until just now.  It looks really cool.

The short answer is: I have no idea.

I've certainly never tested the CM700, and I don't have one handy.  At this precise moment, I haven't really got the spare cycles to acquire one and test.... but I would be exceedingly greatful if you were able to modify the code to work with both the CM700 and the USB2Dynamixel.  The code is already open-source, and I'm happy to accept contributions!

Sorry for the lack-luster reply.

—Travis Deyle

Hi SSR,

USB2Dynamixel is for PC users supported by Dynamixel SDK and CM-700 is 16-bit controller for Dyanmixel (TTL/RS-485) with libraries: 

http://support.robotis.com/en/software/embeded_c/cm510_cm700.htm

I hope you can also check out CM-900 (beta), our new Open Source 32-bit ARM Cortex board... coming SOON!!!! 

http://www.robotsource.org/xe/Circle_CM9_Developer_World

—Jinux

Hi Travis,

Thank you very much for this.  I'm having problems getting it working with an AX-12.  I'm working on a Mac.  To start, I downloaded your file (PySerial already installed from source), checked /dev and found the USB2Dynamixel on <code>tty.usbserial-A96X9BNR </code>- so I ran:

<code> python lib_robotis.py -d /dev/tty.usbserial-A96X9BNR --scan</code>

I get "Scanning for Servos" but nothing.

Then went into your file and I can see that the baud rate is different on an AX-12, and that I need to change the dev_name.  I made that change but still no luck.  When going to the GT ROS repository, I can't see where lib_robotis.py is - could you link directly to the file?  Within the file I've changed the dev_name and baud rate in a few places but I must be missing something.  Thanks again

Updated: Sorry, also tried: <code>python lib_robotis.py -d /dev/tty.usbserial-A96X9BNR --baud 38400 --scan</code> but it returned nothing as well

Updated #2: Used a baud of 1000000 for an AX-12 and it worked. 

—g.cubed

Post new comment

The content of this field is kept private and will not be shown publicly.
  • Web page addresses and e-mail addresses turn into links automatically.
  • Allowed HTML tags: <a> <em> <strong> <cite> <code> <ul> <ol> <li> <dl> <dt> <dd> <p>
  • HTML tags will be transformed to conform to HTML standards.

More information about formatting options