Controlling Dynamixel Motors through USB

This page contains info and tools for controlling the Robotis Dynamixel digital servo motors (RX-28, RX-64, etc) or Bioloid robots (AX-12 and AX-12+ motors) through a USB2Dynamixel adapter (or any RS485 interface).

As you will see, Dynamixel motors provide a lot of power for their small size, but unfortunately they have many faults, particularly with the torque overload shutdown, and feedback from the speed and torque (current).

Dynamixel Toolkit

DynamixelToolkit is a set of open-source command-line tools created for low-level access to Dynamixel motors through a USB2Dynamixel adapter or custom RS485 interface.

Dynamixel Notes:
– Dynamixel motors will shut themselves off if you give them just 30% or 40% of their rated torque! (Read the “Torque” section at the bottom of this page).
– Even though we physically connect the wires of the Dynamixels as a daisy-chain in series, they are wired internally as parallel. So you can easily make a double-adapter or triple-adapter to have multiple daisy-chains in parallel. It also means that if a motor stops communicating, it shouldn’t effect the other motors.
– All these tools assume that there may be lots of electrical noise and communication problems with the motors, so they send lots of repeated commands and perform lots of error checking, to make sure the command gets through reliably.
– To send a command to all Dynamixel motors, use a motor ID if 254 to Broadcast a command to all motors (that are at a certain baudrate).

Command Usage:

Test_Motors [idStartidEnd [baudnum]]
// Display information about all the Dynamixel motors.
// eg: “Test_Motors” will scan all 64 motors at baudrates of 56kbps and 1Mbps (baud 35 and 1) to display complete information about each of the motors.

Show_Pos [idStartidEnd [baudnum [showDebugInfo]]]
// Show the current motor positions for a range of Dynamixel motors.
// eg: “Show_Pos 0 31 35” will display the current motor positions of all 32 motors at a baud of 35 (56kbps).
// eg: “Show_Pos 4 4 1” will display the current motor position of motor 4 at a baud of 1 (1Mbps).

Send_IOidbaudnumoffsetAddr [byteValue]
// Read or Write a single byte to any address of a Dynamixel motor. If you use an id of 254, it will broadcast it to all motors at that baudrate.
// Note that you can use this tool to test basically anything about the motor.
// eg: “Send_IO 2 35 0” will read the value at byte 0 of motor 2 at 35 baud (56kbps). This should display 28 for an RX-28 motor, or 64 for an RX-64 motor, etc.
// eg: “Send_IO 2 35 24” will read the value at byte 24 of motor 2 at 35 baud (56kbps). This should display 0 if the torque is disabled or 1 if torque is currently enabled for the motor.
// eg: “Send_IO 2 1 42” will read the value at byte 42 of motor 2 at 1 baud (1Mbps). This should display the voltage reading of the motor (voltage multiplied by 10).
// eg: “Send_IO 1 35 3 7” will store the value 7 into byte 3 of motor 1 at 35 baud (56kbps). This tells the motor to start using an ID of 7 instead of 1 from now on (even after turning power off).
// eg: “Send_IO 2 35 5 0” will store the value 0 into byte 5 of motor 2 at 35 baud (56kbps). This gives the motor a communication timeout of 0ms instead of 250ms default.

Send_WordidbaudnumoffsetAddr [wordValue]
// Read or Write a word (2 bytes) to any address of a Dynamixel motor. If you use an id of 254, it will broadcast it to all motors at that baudrate.
// eg: “Send_IO 5 1 34” will display the number at bytes 34 & 35 of motor 5 at baud 1 (1Mbps). This should display the current max torque, which is usually high.
// eg: “Send_IO 5 1 32 600” will store the number 600 into bytes 32 & 33 of motor 5 at baud 1 (1Mbps). This should give the motor a max speed of 66 RPM.

Set_Baudidold_baudnumnew_baudnum
// Change the baud rate of a motor. It will keep trying until you hit ESCAPE, in case there is a lot of electrical noise effecting the command to the motor.
// WARNING: If you change the baud rate to a speed that is too fast for you hardware, then might not be able to access it ever again!! (You can try running “Reset_Motor” many times but it might not work). It is recommended to increase the speed by just one baudnum at a time (eg: start with a baud of 34 and then 33 and then 32 and so on, making sure that it works at that speed before jumping all the way to a baud of 1 and never being able to reset it!).
// eg: “Set_Baud 1 35 1” will change a motor with ID 1 from factory default baud of 34 (56kbps baudrate) to the fast baud of 1 (1Mbps).

Enable_Torque [idbaudnum0|1]
// Enable or Disable torque to a Dynamixel motor.
// eg: “Enable_Torque” without arguments will disable torque to all motors (at 1Mbps and 56kbps rates).
// eg: “Enable_Torque 254 35 1” will enable torque to all motors at 35 baud (56kbps).

Reset_Motorid [baudnum]
// Reset a Dynamixel motor to its factory defaults.
// eg: “Reset_Motor 5 35” will reset motor 5 at 1 baud (1Mbps) to its factory default settings.
// eg: “Reset_Motor 5” will try to reset motor 5 to factory default settings using all baud rates from 1Mbps to 56kbps.

Move_Motoridbaudnum [posA [posB]]
// Move a Dynamixel motor to a position, or back & forth between 2 given positions. You can also move the motor manually with UP & DOWN keys, or hit ESC or Spacebar to disable torque.
// eg: “Move_Motor 5 35” will show motor 5’s current position & temperature at 35 baud (56kbps), and let you move it manually with the keyboard up & down keys.
// eg: “Move_Motor 5 1 240 260” will make motor 5 alternate between positions 240 and 260, if it is set to baud 1 (1Mbps).

FrameRecorder REC [file [idStartidEnd [baudnum [waitToRecord [idStart2idEnd2]]]]]
FrameRecorder PLAY [file [idStartidEnd [baudnum [delayFactor [motorSpeed [useRecordedSpeeds]]]]
// Record or Play robot frames, made of Dynamixel motor positions. The 1st line of the frame file stores the variable types and the next line stores the motor ID’s of each column (upto 253). The remaining lines all store the delay (in milliseconds) till the next movement, followed by the motor positions and possibly the motor speeds for that movement. If no speeds are given, then a constant max speed is used for playback, whereas using the recorded speeds results in smoother & more lifelike motions.
// eg: “FrameRecorder REC frames.csv 0 4 35 YES 7 9” will wait till you hit SPACEBAR, then record motors 0 to 4 and 7 to 9 into “frames.csv” if the motors are 35 baud (56kbps).
// eg: “FrameRecorder PLAY frames.csv 0 5 35” will playback the animations for motors 0 to 5 in “frames.csv” at 35 baud (56kbps) at the same speeds as recorded.
// eg: “FrameRecorder PLAY frames.csv 2 4 35 1.0 50 NO” will play just the animations for motors 2, 3 & 4 in “frames.csv” at 35 baud (56kbps) using a max motor speed of 50.

Error Messages when running my programs such as “Show_Pos.exe”:
rxT: Timeout to the motor, probably meaning that the motor is unplugged or damaged.
rxC: Communication error, probably meaning there is a grounding (electrical noise) problem. Could be a bad cable, a ground loop, or a spare cable not being plugged in on both ends!

Torque: (Misleading ratings causing motor shutdown)

Dynamixel motors have very high torque ratings, BUT they have an internal alarm that turns the motors off when you use about 40% of the rated torque! The motor will trip its Current Overload alarm, either instantly or after it is overloaded for too long (which may be after several seconds or even minutes). It does this by changing the maxTorque value to 0, meaning that the motor stops applying torque and therefore rests and cools down. According to the manual, you can detect this alarm condition and set the torque limit back to the max value. But often the motor will be in a frozen state, and actually need its power turned off and back on!

The solution to this is either use the Dynamixels at one third of the rated torque limit, or disable the Current Overload alarm, which can be changed in its EEPROM settings. This means that if you put too much load on the motor, it may eventually damage the motor (burning its electronics or motor windings, or stripping the mechanical gears)! So you should find your own way to make sure you don’t apply too much current to the motor (such as by adding current limiting electronics, or by measuring the electrical current or torque load and disabling it in software if it reaches a high value for several iterations.

If you are having problems with your Dynamixel motors shutting themselves off for no reason, this is probably why!

Sensor Feedback: (Measuring the motor speed or load)

Dynamixels let you read back the position of each motor, to within about 0.5 degrees of accuracy. However, measuring the motor speed or motor torque (‘Present Load’) is a very different story! According to the manufacturer’s comment, the Torque measurement or “Present Load” value is not measured from torque or current, but is simply related to the difference between current position and goal position.

According to a research study by Ethan Tira-Thompson, Dynamixel motors return the motor position within about half a degree of error and at the full communication speed, but motor speed and “Present Load” torque readings only update every 130ms (just 7 times per second!) and aren’t nearly as accurate (roughly 10% error and have dead-zones). On the final page of the report, Ethan mentions that they have been able to trick the controller into reading 3 sensor values within a single 16ms cycle (therefore running 20 motors at roughly 8 frames per second instead of 3).

Timing: (Slow communication with motors)

By default, it takes roughly 18ms to send or receive a command to the motors using a USB2Dynamixel adapter. Luckily, you can use a “Sync Write” to send data to many motors at once, but you can only read data from one motor at a time. So for example, if you have 10 motors, you can move them all to your desired positions in about 18ms but it takes roughly 180ms to read back their actual positions (which is just 5 frames per second)!. If you have 20 motors then this would double to about 360ms (2.5 frames per second)!

In practise, communication is limited to roughly 70 times per second by default (ref: Mike Gebhard) even when using the full 1Mbps baud rate.

However this can be greatly improved. According to a message posted by the manufacturer, the settings can be adjusted to theoretically communicate at upto 500Hz in Windows (ref: Communication Speed). By following their instructions, they say you can reduce the delay in sending & receiving from 16ms delay in the Windows driver to just a 1ms delay!

Changing the motor’s “Return Delay Time” from default 250 to 0 should reduce the delay by another 0.5 ms.

If you use the default 56kbps baud rate, then it will take roughly 1ms extra to send a typical command each way compared to a 1Mbps baud rate.

Dynamixel motors use 9 bits of serial data per byte and usually 7 bytes per command, so it takes roughly 0.5ms to send a command to the motor at 115,200 bps, compared to roughly 0.1ms when using a 1Mbps baud rate. So an extra 0.4ms delay per command may be tolerable for most robots.

This would add up to about 10ms delay when you have 20 motors, in addition to the other delays you would have (such as 1-16ms delays in the USB driver, plus atleast 1ms delay in the operating system, plus 0-0.5ms return delay in the Dynamixel).

But it sounds like the fastest feedback control (reading positions and then sending new positions based on the sensors) that a robot with 20 Dynamixel motors can achieve with the fastest settings is 44ms at 1Mbps ((20+1) * (1+1+0.1)ms delay) or 52ms at 115kbps ((20+1) * (1+1+0.5)ms delay).

So the max speed you can do feedback control of a Dynamixel robot with 20 motors is:

  • 23 frames per second at 1Mbps baud rate
  • 19 frames per second at 115,200bps baud rate

Note that there are ways to improve this, such as by controlling less motors at a time (10 motors is twice as fast as 20), or by interleaving commands (explained here) or using 2 USB2Dynamixel adapters at the same time (this should double the speed since only half the motors are on each adapter).

Remember also, that even though you can control 20 motors at 20Hz based on position, if you want to perform control based on motor speed or motor torque (‘Present Load’), then it can only be done at 7Hz, no matter how many motors you have or what you do!

Leave a Reply

Your email address will not be published. Required fields are marked *