Skip to main content

New XL430-W250 (Released in 2018)

Old XL430-W250 (Discontinued)

Specifications

ItemSpecifications
MCUARM CORTEX-M3 (72 [MHz], 32Bit)
Position SensorContactless absolute encoder (12Bit, 360 [°])
Maker : ams(www.ams.com), Part No : AS5601
MotorCored
Baud Rate9,600 [bps] ~ 4.5 [Mbps]
Control AlgorithmPID control
Resolution4096 [pulse/rev]
Operating ModesVelocity Control Mode
Position Control Mode (0 ~ 360 [°])
Extended Position Control Mode (Multi-turn)
PWM Control Mode (Voltage Control Mode)
Weight57.2 [g]
Dimensions (W x H x D)28.5 x 46.5 x 34 [mm]
Gear Ratio258.5 : 1
Stall Torque1.0 [N.m] (at 9.0 [V], 1.0 [A], 1.000 [Nm/A])
1.4 [N.m] (at 11.1 [V], 1.3 [A], 1.077 [Nm/A])
1.5 [N.m] (at 12.0 [V], 1.4 [A], 1.071 [Nm/A])
No Load Speed47 [rev/min] (at 9.0 [V])
57 [rev/min] (at 11.1 [V])
61 [rev/min] (at 12.0 [V])
Operating Temperature-5 ~ +72 [°C]
Input Voltage6.5 ~ 12.0 [V] (Recommended : 11.1 [V]) (lithium-ion battery 3 Cell)
Command SignalDigital Packet
Physical ConnectionTTL Multidrop Bus (5V Logic)
TTL Half Duplex Asynchronous Serial Communication
(8bit, 1stop, No Parity)
ID253 ID (0 ~ 252)
FeedbackPosition, Velocity, Load, Realtime tick, Trajectory, Temperature, Input Voltage, etc
Case MaterialEngineering Plastic
Gear MaterialEngineering Plastic
Standby Current52 [mA]
danger


DANGER
(Ignoring these warnings may cause serious injury or death)

  • Never place items containing water, flammables/open flames, or solvents near the product.
  • Never place fingers, arms, toes, and other body parts near product during operation.
  • Cease operation and remove power from the product if the product begins to emit strange odors, noises, or smoke.
  • Keep product out of reach of children.
  • Check input polarity before installing or energizing wiring or cables.
warning


CAUTION
(Ignoring these warnings may cause mild injury or damage to the product)

  • Always comply with the product's offical operating environment specifications including input voltage, current, and operating temperature.
  • Do not insert blades or other sharp objects during product operation.
warning


ATTENTION
(Ignoring these warnings may cause minor injury or damage to the product)

  • Do not disassemble or modify the product.
  • Do not drop the product or apply strong impacts.
  • Do not connect or disconnect DYNAMIXEL cables while power is being supplied.

Performance Graph

Looking for the same form factor?

XW430

ModelStall TorqueNo-Load Speed
XW430-T333-R2.9 [N.m] (at 11.1 [V], 1.2 [A])
3.1 [N.m] (at 12.0 [V], 1.3 [A])
3.6 [N.m] (at 14.8 [V], 1.5 [A])
29 [rev/min] (at 11.1 [V]
31 [rev/min] (at 12.0 [V]
39 [rev/min] (at 14.8 [V])
XW430-T200-R6.4 [N.m] (at 11.1 [V], 4.5 [A])
6.9 [N.m] (at 12.0 [V], 4.9 [A])
8.3 [N.m] (at 14.8 [V], 5.9 [A])
49 [rev/min] (at 11.1 [V]
53 [rev/min] (at 12.0 [V]
66 [rev/min] (at 14.8 [V])

XD430

ModelStall TorqueNo-Load Speed
XD430-T350-R3.1 [N.m] (at 11.1 [V], 1.2 [A])
3.4 [N.m] (at 12.0 [V], 1.3 [A])
4.2 [N.m] (at 14.8 [V], 1.5 [A])
27 [rev/min] (at 11.1 [V])
30 [rev/min] (at 12.0 [V])
37 [rev/min] (at 14.8 [V])
XD430-T210-R2.2 [N.m] (at 11.1 [V], 1.2 [A])
2.5 [N.m] (at 12.0 [V], 1.3 [A])
3.1 [N.m] (at 14.8 [V], 1.5 [A])
46 [rev/min] (at 11.1 [V])
50 [rev/min] (at 12.0 [V])
62 [rev/min] (at 14.8 [V])

XH430

ModelStall TorqueNo-Load Speed
XH430-V350-R3.3 [N.m] (at 24 [V], 0.7[A])31 [rev/min] (at 24 [V])
XH430-W350-T/R3.1 [N.m] (at 11.1 [V], 1.2 [A])
3.4 [N.m] (at 12.0 [V], 1.3 [A])
4.2 [N.m] (at 14.8 [V], 1.5 [A])
27 [rev/min] (at 11.1 [V])
30 [rev/min] (at 12.0 [V])
37 [rev/min] (at 14.8 [V])
XH430-V210-R2.6 [N.m] (at 24 [V], 0.7[A])52 [rev/min] (at 24 [V])
XH430-W210-T/R2.2 [N.m] (at 11.1 [V], 1.2 [A])
2.5 [N.m] (at 12.0 [V], 1.3 [A])
3.1 [N.m] (at 14.8 [V], 1.5 [A])
46 [rev/min] (at 11.1 [V])
50 [rev/min] (at 12.0 [V])
62 [rev/min] (at 14.8 [V])

XM430

ModelStall TorqueNo-Load Speed
XM430-W350-T/R3.8 [N.m] (at 11.1 [V], 2.1 [A])
4.1 [N.m] (at 12.0 [V], 2.3 [A])
4.8 [N.m] (at 14.8 [V], 2.7 [A])
43 [rev/min] (at 11.1 [V])
46 [rev/min] (at 12.0 [V])
57 [rev/min] (at 14.8 [V])
XM430-W210-T/R2.7 [N.m] (at 11.1 [V], 2.1 [A])
3.0 [N.m] (at 12.0 [V], 2.3 [A])
3.7 [N.m] (at 14.8 [V], 2.7 [A])
70 [rev/min] (at 11.1 [V])
77 [rev/min] (at 12.0 [V])
95 [rev/min] (at 14.8 [V])

XC430

ModelStall TorqueNo-Load Speed
XC430-W240-T1.4 [N.m] (at 9.0 [V], 1.1 [A])
1.7 [N.m] (at 11.1 [V], 1.3 [A])
1.9 [N.m] (at 12.0 [V], 1.4 [A])
52 [rev/min] (at 9.0 [V])
65 [rev/min] (at 11.1 [V])
70 [rev/min] (at 12.0 [V])
XC430-W150-T1.2 [N.m] (at 9.0 [V], 1.1 [A])
1.4 [N.m] (at 11.1 [V], 1.3 [A])
1.6 [N.m] (at 12.0 [V], 1.4 [A])
80 [rev/min] (at 9.0 [V])
99 [rev/min] (at 11.1 [V])
106 [rev/min] (at 12.0 [V])
XC430-T240BB-T1.4 [N.m] (at 9.0 [V], 1.1 [A])
1.7 [N.m] (at 11.1 [V], 1.3 [A])
1.9 [N.m] (at 12.0 [V], 1.4 [A])
52 [rev/min] (at 9.0 [V])
65 [rev/min] (at 11.1 [V])
70 jrev/min] (at 12.0 [V])
XC430-T150BB-T1.2 [N.m] (at 9.0 [V], 1.1 [A])
1.4 [N.m] (at 11.1 [V], 1.3 [A])
1.6 [N.m] (at 12.0 [V], 1.4 [A])
80 [rev/min] (at 9.0 [V])
99 [rev/min] (at 11.1 [V])
106 [rev/min] (at 12.0 [V])

XL430

ModelStall TorqueNo-Load Speed
XL430-W250-T1.0 [N.m] (at 9.0 [V], 1.0 [A])
1.4 [N.m] (at 11.1 [V], 1.3 [A])
1.5 [N.m] (at 12.0 [V], 1.4 [A])
47 [rev/min] (at 9.0 [V])
57 [rev/min] (at 11.1 [V])
61 [rev/min] (at 12.0 [V])
note

NOTE : The given Stall torque rating for a servo is different from it's continuous output rating, and may also differ from it's expected real world performance.

Stall torque is the maximum momentary torque output the servo is capable of, an is generally how RC servos are measured. The Performance graph, or N-T curve, from the above graph is measured under conditions simulating a gradually increasing load.

Generally, the Maximum Torque shown through Performance Graph testing is less than the maximum Stall Torque.

The actual real world performance of the servo will generally be closer to the performance graph measurements, not the rated stall torque.

warning

CAUTION - When supplying power:

  • It is recommended to use a ROBOTIS controller or SMPS2DYNAMIXEL power adapter.

  • Do not connect or disconnect DYNAMIXEL actuator cables while power is being supplied.

Control Table

The Control Table is a data structure used by DYNAMIXEL actuators to manage the state of the device. Users can read data registers to get information about the status of the device with Read Instruction Packets, and modify data registers to control the device with Write Instruction Packets.

Control Table, Data, Address

The Control Table is a structure that consists of multiple Data fields to store status or to control the device. Users can check current status of the device by reading a specific Data from the Control Table with Read Instruction Packets. WRITE Instruction Packets enable users to control the device by changing specific Data in the Control Table. The Address is a unique value when accessing a specific Data in the Control Table with Instruction Packets. In order to read or write data, users must designate a specific Address in the Instruction Packet. Please refer to DYNAMIXEL Protocol 2.0 for more details about Instruction Packets.

note

NOTE : Two's complement is applied for the negative value. For more information, please refer to Two's complement from Wikipedia.

Area (EEPROM, RAM)

The Control Table is divided into 2 Areas. Data in the RAM Area is reset to initial values when the power is reset(Volatile). On the other hand, data in the EEPROM Area is maintained even when the device is powered off(Non-Volatile).

warning

Data in the EEPROM Area can only be written to if Torque Enable(64) is cleared to '0'(Torque OFF).

Size

The Size of data varies from 1 ~ 4 bytes depend on their usage. Please check the size of data when updating the data with an Instruction Packet. For data larger than 2 bytes will be saved according to Little Endian.

Access

The Control Table has two different access properties. ‘RW’ property stands for read and write access permission while ‘R’ stands for read only access permission. Data with the read only property cannot be changed by the WRITE Instruction. Read only property(‘R’) is generally used for measuring and monitoring purpose, and read write property(‘RW’) is used for controlling device.

Initial Value

Each data in the Control Table is restored to initial values when the device is turned on. Default values in the EEPROM area are initial values of the device (factory default settings). If any values in the EEPROM area are modified by a user, modified values will be restored as initial values when the device is turned on. Initial Values in the RAM area are restored when the device is turned on.

Control Table of EEPROM Area

AddressSize(Byte)Data NameAccessInitial
Value
RangeUnit
02Model NumberR1,060--
24Model InformationR---
61Firmware VersionR---
71IDRW10 ~ 252-
81Baud RateRW10 ~ 7-
91Return Delay TimeRW2500 ~ 2542 [μsec]
101Drive ModeRW00 ~ 13-
111Operating ModeRW30 ~ 16-
121Secondary(Shadow) IDRW2550 ~ 252-
131Protocol TypeRW21 ~ 2-
204Homing OffsetRW0-1,044,479 ~
1,044,479
1 [pulse]
244Moving ThresholdRW100 ~ 1,0230.229 [rev/min]
311Temperature LimitRW720 ~ 1001 [°C]
322Max Voltage LimitRW14060 ~ 1400.1 [V]
342Min Voltage LimitRW6060 ~ 1400.1 [V]
362PWM LimitRW8850 ~ 8850.113 [%]
444Velocity LimitRW2650 ~ 1,0230.229 [rev/min]
484Max Position LimitRW4,0950 ~ 4,0951 [pulse]
524Min Position LimitRW00 ~ 4,0951 [pulse]
601Startup ConfigurationRW03-
631ShutdownRW52--

Control Table of RAM Area

AddressSize(Byte)Data NameAccessInitial
Value
RangeUnit
641Torque EnableRW00 ~ 1-
651LEDRW00 ~ 1-
681Status Return LevelRW20 ~ 2-
691Registered InstructionR00 ~ 1-
701Hardware Error StatusR0--
762Velocity I GainRW1,0000 ~ 16,383-
782Velocity P GainRW1000 ~ 16,383-
802Position D GainRW4,0000 ~ 16,383-
822Position I GainRW00 ~ 16,383-
842Position P GainRW6400 ~ 16,383-
882Feedforward 2nd GainRW00 ~ 16,383-
902Feedforward 1st GainRW00 ~ 16,383-
981Bus WatchdogRW01 ~ 12720 [msec]
1002Goal PWMRW--PWM Limit(36) ~
PWM Limit(36)
0.113 [%]
1044Goal VelocityRW--Velocity Limit(44) ~
Velocity Limit(44)
0.229 [rev/min]
1084Profile AccelerationRW00 ~ 32,767
0 ~ 32,737
214.577 [rev/min2]
1 [ms]
1124Profile VelocityRW00 ~ 32,7670.229 [rev/min]
1164Goal PositionRW-Min Position Limit(52) ~
Max Position Limit(48)
1 [pulse]
1202Realtime TickR-0 ~ 32,7671 [msec]
1221MovingR00 ~ 1-
1231Moving StatusR0--
1242Present PWMR---
1262Present LoadR--1,000 ~ 1,0000.1 [%]
1284Present VelocityR--0.229 [rev/min]
1324Present PositionR--1 [pulse]
1364Velocity TrajectoryR--0.229 [rev/min]
1404Position TrajectoryR--1 [pulse]
1442Present Input VoltageR--0.1 [V]
1461Present TemperatureR--1 [°C]
1471Backup ReadyR-0 ~ 1-
1682Indirect Address 1RW22464 ~ 661-
1702Indirect Address 2RW22564 ~ 661-
1722Indirect Address 3RW22664 ~ 661-
--
2182Indirect Address 26RW24964 ~ 661-
2202Indirect Address 27RW25064 ~ 661-
2222Indirect Address 28RW25164 ~ 661-
2241Indirect Data 1RW00 ~ 255-
2251Indirect Data 2RW00 ~ 255-
2261Indirect Data 3RW00 ~ 255-
--
2491Indirect Data 26RW00 ~ 255-
2501Indirect Data 27RW00 ~ 255-
2511Indirect Data 28RW00 ~ 255-
5782Indirect Address 29RW63464 ~ 661-
5802Indirect Address 30RW63564 ~ 661-
5822Indirect Address 31RW63664 ~ 661-
--
6282Indirect Address 54RW65964 ~ 661-
6302Indirect Address 55RW66064 ~ 661-
6322Indirect Address 56RW66164 ~ 661-
6341Indirect Data 29RW00 ~ 255-
6351Indirect Data 30RW00 ~ 255-
6361Indirect Data 31RW00 ~ 255-
--
6591Indirect Data 54RW00 ~ 255-
6601Indirect Data 55RW00 ~ 255-
6611Indirect Data 56RW00 ~ 255-
warning

CAUTION : Protocol 1.0 does not support addresses greater than 256. Therefore, Indirect Address 29 ~ 56 and Indirect Data 29 ~ 56 can only be accessed with Protocol 2.0.

Control Table Description

warning

CAUTION : Data in the EEPROM Area can only be modified when the value of Torque Enable(64) is set to ‘0’.

Model Number(0)

This address stores the model number of your DYNAMIXEL servo.

Decimal ValueHex ValueModel Name
10600x0424XL430-W250

Firmware Version(6)

This address stores the version number of the current firmware running on your DYNAMIXEL servo.

ID(7)

The ID assigned to a DYNAMIXEL actuator is a unique value used to identify a specific actuator through the DYNAMIXEL network. The numbers 0-253 (0xFD) can be assigned as an ID, with 254 (0xFE) reserved for use as the Broadcast ID that can send an Instruction Packet to all connected DYNAMIXEL servos simultaneously.

note

NOTE : IDs for every DYNAMIXEL connected to a single network must be unique. Shared ID numbers may cause communication failure.

note

NOTE : If an Instruction Packet ID is set to the Broadcast ID(0xFE), Status Packets will not be returned for READ or WRITE Instructions regardless of the configured Status Return Level (68). For more details, please refer to the Status Packet of the [DYNAMIXEL Protocol 2.0] eManual page.

Baud Rate(8)

The Baud Rate(8) determines serial communication speed between a controller and DYNAMIXEL.

ValueBaud RateMargin of Error
74.5M [bps]0.000 [%]
64M [bps]0.000 [%]
53M [bps]0.000 [%]
42M [bps]0.000 [%]
31M [bps]0.000 [%]
2115,200 [bps]0.000 [%]
1(Default)57,600 [bps]0.000 [%]
09,600 [bps]0.000 [%]
note

NOTE : Less than 3% of the baud rate error margin will not affect to UART communication.

note

NOTE : For the stable communication with higher Baudrate using U2D2, configure USB Latency value to the lower.
USB Latency Setting

Return Delay Time(9)

When a DYNAMIXEL receives an Instruction Packet, it will return a Status Packet response after the configured Return Delay Time(9) has passed. The range of configurable values for this setting is 0 to 254 (0XFE) in units of 2 [μsec]. For instance, if the Return Delay Time(9) is set to ‘10’, a Status Packet will be returned 20[μsec] after an Instruction Packet is received.

UnitValue RangeDescription
2[μsec]0 ~ 254Default value ‘250’(500[μsec])
Maximum value: '508'[μsec]

Drive Mode(10)

Drive Mode contains several settings for adjusting the operating behavior of DYNAMIXEL servos, including automatic torque on, reverse movement, and movement profiles.

BitItemDescription
Bit 7(0x80)-Unused, always ‘0’
Bit 6(0x40)-Unused, always ‘0’
Bit 5(0x20)-Unused, always ‘0’
Bit 4(0x10)-Unused, always ‘0’
Bit 3(0x08)Torque On by Goal Update[0] Movements will only be executed if [Torque Enable(64)] is set to '1'
[1] Movements will be executed regardless of the value of [Torque Enable(64)]. If the value of Torque Enable(64) is '0' and a command is given, Torque Enable(64) will be updated to '1'.
Bit 2(0x04)Profile Configuration[0] Velocity-based Profile: Create Profiles based on movement Velocity
[1] Time-based Profile: Create Profiles based on time steps.
※ See What is the Profile
Bit 1(0x02)-Unused, always ‘0’
Bit 0(0x01)Normal/Reverse Mode[0] Normal Mode: CCW(Positive), CW(Negative)
[1] Reverse Mode: CCW(Negative), CW(Positive)
note

NOTE : Time-based Profile is available starting from firmware V42.

note

NOTE: Torque On by Goal Update is available starting from firmware V45.

note

NOTE : If the value of Bit 0(Normal/Reverse Mode) of Drive Mode(10) is set to 1, rotational direction is inverted.
Thus, Goal Position, Present Position will also have inverted directions. This feature can be very useful when configuring symmetrical joints, or similar mirrored DYNAMIXEL installations.

Operating Mode(11)

ValueOperating ModeDescription
1Velocity Control ModeThis mode controls velocity. This mode behaves similarly to a standard DC motor, and is best suited to applications like drive wheels.
3(Default)Position Control ModeThis mode controls position. This mode is identical to the Joint Mode from existing DYNAMIXEL. Operating position range is limited by the [Max Position Limit(48)] and the [Min Position Limit(52)]. This mode is ideal for articulated robots that each joint rotates less than 360 degrees.
4Extended Position Control Mode(Multi-turn)This mode controls position. This mode is identical to the Multi-turn Position Control from existing DYNAMIXEL. 512 turns are supported(-256[rev] ~ 256[rev]). This mode is ideal for multi-turn wrists or conveyer systems or a system that requires an additional reduction gear. Note that [Max Position Limit(48)], [Min Position Limit(52)] are not used on Extended Position Control Mode.
16PWM Control Mode (Voltage Control Mode)This mode directly controls PWM output. (Voltage Control Mode)
note

NOTE : When the value of the Operating Mode(11) register changes, the Velocity PI(76, 78); Position PID(80, 82, 84); Feedforward(88, 90), will be reset according to the selected Operating Mode(11). Aside from this, the following registers will also be reset:

  1. Profile Velocity(112) and Profile Acceleration(108) will be set to ‘0’
  2. Goal PWM(100) is reset to the value of PWM Limit(36)
note

NOTE : PWM stands for Pulse Width Modulation, the signal that modulates voltage to control motors. It changes pulse width to control average supply voltage to the motor, and this technique is widely used in the motor control field.
PWM Control Mode is similar to the Wheel Mode of AX and RX series. Goal PWM(100) is used to control supply voltage for DYNAMIXELs in PWM Control Mode.

Secondary(Shadow) ID(12)

Secondary(Shadow) ID(12) allows the assignment of a secondary ID to a DYNAMIXEL.
The Secondary ID(12) can be used to group DYNAMIXELs and to synchronize their movement unlike the primary [ID(7)], which must be unique, any number of connected DYNAMIXELs may share a Secondary ID(12). There are several important differences between the primary [ID(7)] and Secondary ID(12):

  • [ID(7)] has a greater priority than Secondary ID(12). If Secondary ID(12) and [ID(7)] are the same, the actuator will respond as if commands are sent only to it's primary [ID(7)].
  • The EEPROM area of the Control Table cannot be modified with control packets addressed to a Secondary ID(12).
  • Status Packets will not be returned for commands sent to Secondary ID(12).
  • If the value of Secondary ID(12) is 253 or higher, the Secondary ID function will be deactivated.
ValuesDescription
0 ~ 252Activate Secondary ID function
253 ~ 255Deactivate Secondary ID function, Default value ‘255’

Secondary ID(12) Example

See the following Secondary ID(12) example for a demonstration. Note that the assigned [ID(7)] for the DYNAMIXELs in the example are '1', '2', '3', '4' and '5'.

  1. Set the Secondary ID of the five connected DYNAMIXELs to '5'
  2. Send a Write Instruction Packet([ID(7)] = 1, [LED(65)] = 1).
  3. The DYNAMIXEL with [ID(7)]1' turns on its LED and a Status Packet will be returned.
  4. Send Write Instruction Packet([ID(7)] = 5, [LED(65)] = 1).
  5. All DYNAMIXELs turn on their LED, but only the actuator with an [ID(7)] of '5' will return a Status Packet.
  6. Set the Secondary ID of all DYNAMIXELs to ‘100’.
  7. Send Write Instruction Packet([ID(7)] = 100, [LED(65)] = 0).
  8. All DYNAMIXELs turn off their LED. As no DYNAMIXEL uses ID 100, no Status Packet will be returned.

Protocol Type(13)

Protocol Type(13) is used to set the communications protocol used by the DYNAMIXEL actuator.

warning

WARNING : To modify the Protocol Type(13), use DYNAMIXEL Wizard 2.0 as R+ Manager 2.0 is not compatible with Protocol 1.0 products.

note

NOTE : Protocol 2.0 is more stable and safe for use than Protocol 1.0. Accessing some of the Control Table area might be denied if Protocol 1.0 is selected. Please refer to the [Protocol 1.0] and [Protocol 2.0] of e-Manual for more details about the protocol.

The following table lists available protocol types compatible with this model of DYNAMIXEL.

ValueDescriptionCompatible DYNAMIXEL
1DYNAMIXEL Protocol 1.0AX Series, DX Series, RX Series, EX Series, MX Series with Firmware below v39
2(default)DYNAMIXEL Protocol 2.0MX-28/64/106 with Firmware v39 or above, X Series, PRO Series
note

NOTE : Please refer to the Protocol Compatibility table to see a listing of supported protocols by product.

Homing Offset(20)

Homing Offset(20) allows users to adjust the actuator's home position by adding the offset value is to the reported [Present Position(132)].

Present Position(132) = Actual Position + Homing Offset(20)

UnitValue Range
about 0.088 [°]-1,044,479 ~ 1,044,479
(-255 ~ 255[rev])
note

NOTE : In Position Control Mode(Joint Mode) when configured to rotate less than 360 degrees, any invalid Homing Offset(20) values will be ignored(valid range : -1,024 ~ 1,024).

warning

WARNING : Even if Drive Mode(10) is set to Reverse Mode, the sign of the Homing Offset(20) value is not reversed.

Moving Threshold(24)

The Moving Threshold(24) is used to determine whether the DYNAMIXEL is considered to be in motion or not. When the absolute value of the [Present Velocity(128)] is greater than the configured Moving Threshold(24), the DYNAMIXEL is considered in motion and the value of [Moving(122)] is set to ‘1’.

UnitRangeDescription
about 0.229 rpm0 ~ 1,023All velocity related Data uses the same unit scale

Temperature Limit(31)

The Temperature Limit(31) is used to configure an upper limit on DYNAMIXEL operating temperature.
When the [Present Temperature(146)] is greater than the Temperature Limit(31), the Overheating Error Bit(0x04) and Alert Bit(0x80) in the [Hardware Error Status(70)] register will be set. If the Overheating Error Bit(0x04) is configured in [Shutdown(63)], [Torque Enable(64)] will be set to ‘0’ (Torque OFF). See [Shutdown(63)] for more detailed information.

UnitValue RangeDescription
About 1°0 ~ 1000 ~ 100°
warning

CAUTION : Do not set this value higher than it's default. In the case that a DYNAMIXEL triggers a temperature shutdown alarm (Overheating Error Bit(0x04)), let it cool for 20 minutes or more before resuming use to prevent damage to the actuator.

Min/Max Voltage Limit(34, 32)

The Min Voltage Limit(32) and Max Voltage Limit(34) are used to configure the range of acceptable input voltages. When the [Present Input Voltage(144)] exits the range between Max Voltage Limit(32) and Min Voltage Limit(34), the Input Voltage error Bit(0x10) in the Hardware Error Status(70) will be set, and the returned Status Packet will contain an Alert Bit(0x80) in the Error field.
If the Input Voltage Error Bit(0x10) in the [Shutdown(63)] register is set, [Torque Enable(64)] will be set to ‘0’(Torque OFF).
For more details, please refer to [Shutdown(63)].

UnitValue RangeDescription
About 0.1 [V]65 ~ 1406.5 ~ 14.0 [V]

PWM Limit(36)

The PWM Limit(36) is used to configure the maximum allowable PWM output. [Goal PWM(100)] can’t be set to a values exceeding the [PWM Limit(36)]. Additionaly, the [PWM Limit(36)] is used in all operating mode as an absolute limit to the motor's final output PWM. For more details, please refer to the Gain section of each operating mode.

UnitRange
about 0.113 [%]0(0 [%]) ~ 885(100 [%] )

Velocity Limit(44)

The Velocity Limit(44) is used to limit the maximum acceptable value for the [Goal Velocity(104)]. For more details, see [Goal Velocity(104)].

UnitValue Range
0.229rpm0 ~ 1,023

Min/Max Position Limit(52, 48)

The Min and Max Position Limit(48, 52) is used to configure the maximum movement range in Position Control Mode within a single rotation(0 ~ 4,095).
Provided [Goal Position(116)] values must be within the configured position limit range.

UnitValue Range
0.088 [°]0 ~ 4,095(1 rotation)
warning

NOTE : Max Position Limit(48) and Min Position Limit(52) are only used in Position Control Mode within a single turn. The angle limits set through this control table item do not apply in Extended Position Control Mode.

Startup Configuration(60)

Startup Configuration(60) allows users to configure several settings to apply on actuator startup. See the following table for information on available settings.

BitItemDescription
Bit 7(0x80)-Unused, always ‘0’
Bit 6(0x40)-Unused, always ‘0’
Bit 5(0x20)-Unused, always ‘0’
Bit 4(0x10)-Unused, always ‘0’
Bit 3(0x08)-Unused, always ‘0’
Bit 2(0x04)-Unused, always ‘0’
Bit 1(0x02)RAM Restore[0] Deactivate RAM restoration on startup.
[1] On startup, use saved backup data to restore RAM configuration.
Bit 0(0x01)Startup Torque On[0] Torque Off on startup (Torque Enable(64) is set to 0)
[1] Torque On on startup (Torque Enable(64) is set to 1).
note

NOTE: Startup Configuration is available from firmware V45.

note

NOTE: For more details about restoring the RAM area, see Restoring RAM Area.

Shutdown(63)

DYNAMIXEL servos can protect themselves by detecting dangerous situations that may occur during operation. This register allows user to configure which of these error states causes a safety shutdown. Each Bit is inclusively processed with ‘OR’ logic, allowing multiple options to be selected. For instance, when Shutdown(63) is set to ‘0x05’ (binary : 00000101), the DYNAMIXEL will shutdown in response to both both an Input Voltage Error(binary : 00000001) and Overheating Error(binary : 00000100). If those errors are detected, [Torque Enable(64)] is cleared to ‘0’ and the motor's output will be set to 0 [%].

A REBOOT is the only method to reset [Torque Enable(64)] to ‘1’(Torque ON) after a shutdown has been triggered.

BitItemDescription
Bit 7-Unused, Always '0'
Bit 6-Unused, Always '0'
Bit 5Overload Error(default)Detects that persistent load that exceeds maximum output
Bit 4Electrical Shock Error(default)Detects electric shock on the circuit or insufficient power to operate the motor
Bit 3Motor Encoder ErrorDetects malfunction of the motor encoder
Bit 2Overheating Error(default)Detects that internal temperature exceeds the configured operating temperature
Bit 1-Unused, Always '0'
Bit 0Input Voltage ErrorDetects that input voltage exceeds the configured operating voltage
note

NOTE :

  1. If Shutdown occurs, the indicator LED will flicker every second. (Firmware v41 or above)
  2. If a Shutdown occurs, reboot the device to restore functionality.
  • H/W REBOOT : Turn off and turn on the power to the actuator.
  • S/W REBOOT : Transmit REBOOT Instruction (For more details, refer to the Reboot section of the e-Manual.)

Torque Enable(64)

Torque Enable(64) is used to enable or disable the torque for the DYNAMIXEL's internal motor. Setting Torque Enable(64) to ‘1’ will enable output Torque and all Data in the EEPROM area will be locked. Setting the value to ‘0’ will disable torque and unlock the EEPROM.

ValueDescription
0(Default)Torque Off, EEPROM unlocked
1Torque On, EEPROM locked
note

NOTE : [Present Position(132)] will be reset when the [Operating Mode(11)] or [Torque Enable(64)] settings are updated. For more details, please refer to the [Homing Offset(20)] and [Present Position(132)] control table items.

LED(65)

LED(65) controls the state of the indicator LED located on the back of the DYNAMIXEL actuator.

BitDescription
0(Default)Turn OFF the LED
1Turn ON the LED

Status Return Level(68)

The Status Return Level (68) is used to set the DYNAMIXEL's response policy when an instruction packet is received.

ValueResponding InstructionsDescription
0PING InstructionReturns a Status Packet for PING Instructions only
1PING Instruction
READ Instruction
Returns a Status Packet for PING and READ Instructions
2All InstructionsReturns a Status Packet for all Instructions
note

NOTE : If the Instruction Packet ID is set to the Broadcast ID(0xFE), a Status Packet will not be returned for READ or WRITE Instructions regardless of Status Return Level (68). For more details, please refer to the Status Packet section of the [DYNAMIXEL Protocol 2.0] page.

Registered Instruction(69)

Indicates whether an instruction has been registered by the Reg Write Instruction and is ready for execution. Following the execution of a registered action the Registered Instruction (69) value will automatically be updated to 0.

ValueDescription
0No instruction registered by REG_WRITE.
1Instruction registered by REG_WRITE.

Hardware Error Status(70)

This register stores any active hardware error status conditions. For more details, please refer to the Shutdown(48) control table item.

Velocity PI Gain(76, 78)

The Velocity PI Gains(76, 78) are the configurable gain settings for the DYNAMIXEL PID controller in Velocity Mode.

Controller GainConversion EquationsRangeDescription
Velocity I Gain(76)KVIKVI = KVI(TBL) / 65,5360 ~ 16,383I Gain
Velocity P Gain(78)KVPKVP = KVP(TBL) / 1280 ~ 16,383P Gain

When an instruction transmitted from the user is received by a DYNAMIXEL servo, it takes the following steps to generate a trajectory and execute a motion.

  1. An Instruction from the user is transmitted via the DYNAMIXEL bus, then written to [Goal Velocity(104)].
  2. [Goal Velocity(104)] is converted to planned velocity trajectory by the configured [Profile Acceleration(108)].
  3. The desired velocity trajectory is stored at [Velocity Trajectory(136)].
  4. The PI controller calculates PWM output for the motor based on the desired velocity trajectory.
  5. [Goal PWM(100)] sets a limit on the calculated PWM output and decides the final PWM value.
  6. The final PWM value is applied to the motor through an Inverter, and the horn of the DYNAMIXEL is driven.
  7. Results are stored at [Present Position(132)], [Present Velocity(128)], [Present PWM(124)] and [Present Load(126)].

The below figure is a block diagram describing the velocity controller in Velocity Control Mode.

note

NOTE : Ka Anti-windup Gain and β are conversion coefficients of position and velocity that cannot be modified by users. For more information about PID controllers in general, please refer to the PID Controller article on Wikipedia.

Position PID Gain(80, 82, 84), Feedforward 1st/2nd Gains(88, 90)

The Position PID Gains(76, 78) are the configurable gain settings for the DYNAMIXEL PID controller in Position Control Mode and Extended Position Control Mode.

Controller GainConversion EquationsRangeDescription
Position D Gain(80)KPDKPD = KPD(TBL) / 160 ~ 16,383D Gain
Position I Gain(82)KPIKPI = KPI(TBL) / 65,5360 ~ 16,383I Gain
Position P Gain(84)KPPKPP = KPP(TBL) / 1280 ~ 16,383P Gain
Feedforward 2nd Gain(88)KFF2ndKFF2nd(TBL) / 40 ~ 16,383Feedforward Acceleration Gain
Feedforward 1st Gain(90)KFF1stKFF1st(TBL) / 40 ~ 16,383Feedforward Velocity Gain

When an instruction transmitted from the user is received by a DYNAMIXEL servo, it takes the following steps to generate a trajectory and execute a motion.

  1. An Instruction from the user is transmitted via the DYNAMIXEL bus, then registered to [Goal Position(116)].
  2. [Goal Position(116)] is converted to desired position trajectory and desired velocity trajectory by [Profile Velocity(112)] and [Profile Acceleration(108)].
  3. The desired position trajectory and desired velocity trajectory is stored in the [Position Trajectory(140)] and [Velocity Trajectory(136)] registers.
  4. The Feedforward and PID controller calculate PWM output for the motor based on desired trajectories.
  5. [Goal PWM(100)] is used as a limit on the calculated PWM output and decides the final output PWM value.
  6. The final PWM value is applied to the motor through an inverter, and the horn of the DYNAMIXEL is driven.
  7. Results are stored at [Present Position(132)], [Present Velocity(128)], [Present PWM(124)] and [Present Load(126)].

The figure below is a block diagram describing the position controller in Position Control Mode and Extended Position Control Mode.

note

NOTE:

  • In PWM Control Mode, both the internal PID controller and Feedforward controller are deactivated while Goal PWM(100) is used to directly control the voltage to the motor.
  • Ka is an Anti-windup Gain that cannot be modified by users.
  • For more details about PID controllers and Feedforward controllers in general, please refer to the PID Controller and Feed Forward Wikipedia articles.

Bus Watchdog(98)

The Bus Watchdog(98) is a fail-safe system used to stop DYNAMIXEL motion if communication between the controller and DYNAMIXEL (RS-485, TTL) is disconnected.

ValuesDescription
Range0Deactivate Bus Watchdog Function, Clear Bus Watchdog Error
Range1 ~ 127Activate Bus Watchdog (Unit: 20 [msec])
Range-1Bus Watchdog Error Active

The Bus Watchdog function monitors the interval of communications between the controller and DYNAMIXEL when [Torque Enable(64)] is '1'(Torque ON).
If the measured communication interval is larger than the configured value of Bus Watchdog(98), the DYNAMIXEL will stop. Bus Watchdog(98) will be changed to '-1' and a Bus Watchdog Error will be activated. When a Bus Watchdog Error screen is active, all Goal Values ([Goal PWM(100)], [Goal Velocity(104)], [Goal Position(116)]) will be changed to read-only-access until the error has been cleared. If the value of Bus Watchdog(98) is changed to '0', active Bus Watchdog Errors will be cleared.

Bus Watchdog (98) Example

The following is an example of the operation of the Bus Watchdog failsafe.

  1. After setting the [Operating Mode(11)] to speed control mode, change [Torque Enable(64)] to '1'.
  2. If '50' is written to [Goal Velocity(104)], the DYNAMIXEL will rotate in a CCW direction.
  3. Change the value of [Bus Watchdog(98)] to '100' (2,000 [ms]) to activate the Bus Watchdog function.
  4. If no instruction packet is received for 2,000 [ms], the DYNAMIXEL will stop. When it stops, the [Profile Acceleration(108)] and [Profile Velocity(112)] are set to '0'.
  5. The value of [Bus Watchdog(98)] changes to '-1' (Bus Watchdog Error). At this time, the access to Goal Values will be changed to read-only.
  6. If '150' is written to [Goal Velocity(104)], a Data Range Error will be returned via Status Packet.
  7. If the value of [Bus Watchdog(98)] is changed to '0', the Bus Watchdog Error will be cleared.
  8. If “150” is written to [Goal Velocity(104)], the DYNAMIXEL will rotate in a CCW direction.

Goal PWM(100)

When the [Operating Mode(11)] is set to PWM Control Mode, both the internal PID and Feedforward controllers will be deactivated and Goal PWM(100) is used to directly control the supplied output voltage to the servo's motor. When set to a different [Operating Mode(11)], Goal PWM(100) is used as a final limiter on the output PWM value only. Read Position PID Gain(80, 82, 84), Feedforward 1st/2nd Gains(88, 90) or Velocity PI Gain(76, 78) for more information on how Goal PWM (100) works with configurable gain settings.

UnitRange
about 0.113 [%]-[PWM Limit(36)] ~ [PWM Limit(36)]
note

NOTE: Goal PWM(100) can not exceed the configured [PWM Limit(36)].

Goal Velocity(104)

Goal Velocity(104) is used to to set the target velocity when in the Velocity Control Mode [Operating Mode(11)]. Goal Velocity(104) is not used to limit moving velocity in any operating modes.

UnitValue Range
0.229 rpm-[Velocity Limit(44)] ~ [Velocity Limit(44)]
note

NOTE: Goal Velocity(104) can not exceed the configured [Velocity Limit(44)].

note

NOTE : The maximum velocity and maximum torque of DYNAMIXEL is affected by the supplied voltage. If the input voltage changes, so does the maximum velocity and torque. This manual assumes operation with the recommended input voltage.

note

NOTE : If [Profile Acceleration(108)] and Goal Velocity(104) are modified simultaneously, the newly modified [Profile Acceleration(108)] will be used to process the updated Goal Velocity(104).

Profile Acceleration(108)

When the [Drive Mode(10)] is Velocity-based Profile, Profile Acceleration(108) sets the maximum allowable acceleration of the generated Profile.
When the [Drive Mode(10)] is Time-based Profile, Profile Acceleration(108) sets the allowed acceleration time of the generated Profile.
The Profile Acceleration(108) is used in all control modes except Current Control Mode and PWM Control Mode.

For more detailed information, see What is the Profile

Velocity-based ProfileValuesDescription
Unit214.577 [rev/min2]Sets maximum acceleration of the Profile
Range0 ~ 32767'0' represents an infinite maximum acceleration
Time-based ProfileValuesDescription
Unit1 [msec]Sets allowed acceleration time of the Profile
Range0 ~ 32737'0' represents an infinite acceleration time('0 [msec]').
Profile Acceleration(108) can not exceed 50% of the configured Profile Velocity (112) value.
note

NOTE : Time-based Profiles are available starting from firmware version 42.

Profile Velocity(112)

When the [Drive Mode(10)] is Velocity-based Profile, Profile Velocity(112) sets the maximum allowable velocity of the generated Profile.
When the [Drive Mode(10)] is Time-based Profile, Profile Velocity(112) sets the total execution time of the generated Profile. Profile Velocity(112) is only applied in the Position Control Mode or Extended Position Control Mode [Operating Mode(11)].

For more detailed information, see What is the Profile.

note

NOTE: Velocity Control Mode only uses [Profile Acceleration(108)]

Velocity-based ProfileValuesDescription
Unit0.229 [rev/min]Sets the maximum velocity of the Profile
Range0 ~ 32767'0' represents an infinite velocity
Time-based ProfileValuesDescription
Unit1 [msec]Sets the time span for the Profile
Range0 ~ 32737'0' represents an infinite velocity.
Profile Acceleration(108) can not exceed 50% of the configured Profile Velocity (112) value.
note

NOTE : Time-based Profiles are available from firmware V42.

Goal Position(116)

Goal Position(116) is used to set the actuator's desired output position.

ModeValuesDescription
Position Control ModeMin Position Limit(52) ~ Max Position Limit(48)Initial Value : 0 ~ 4,095
Extended Position Control Mode-1,048,575 ~ 1,048,575-256[rev] ~ 256[rev]
UnitDescription
0.088 [deg/pulse]1[rev] : 0 ~ 4,095 (1 rotation (0 ~ 4,095, total 4,096 counts))
note

NOTE : Profile Velocity(112) and Profile Acceleration(108) are active under the following conditions:

note

NOTE : When turning off the power supply or changing the Operating Mode to Extended Position Control Mode, the value of Present Position is reset to the absolute position value within a single turn.

Realtime Tick(120)

Realtime Tick(120) tracks the uptime of the current DYNAMIXEL actuator. This register begins counting at 0 when the actuator is powered on.

UnitValue RangeDescription
1 ms0 ~ 32,767The value resets to '0' when it exceeds 32,767

Moving(122)

The Moving(122) register indicates whether the connected DYNAMIXEL is in motion or not.
If the absolute value of [Present Velocity(128)] is greater than the configured [Moving Threshold(24)], Moving(122) is set to '1', indicating the actuator is currently in motion. Otherwise, it will be cleared to '0'. However, Moving(122) will always be set to '1' regardless of [Present Velocity(128)] while a movement Profile is in progress following an updated [Goal Position(116)] instruction.

ValueDescription
0Movement is not detected
1Movement is detected, or a Profile is in progress(Goal Position(116) instruction has been updated)

Moving Status(123)

Moving Status(123) is a collection of bits that provide additional information about the DYNAMIXEL's current motion status.

BitValueInformationDescription
Bit 7X-Reserved for future use
Bit 6X-Reserved for future use
Bit 4
Bit 5
11
10
01
00
Velocity Profile11 : Trapezoidal Profile
10 : Triangular Profile
01 : Rectangular Profile
00 : Profile not used(Step)
Bit 30 or 1Following ErrorWhether or not the DYNAMIXEL is following the desired position trajectory
0 : Following
1 : Not following
Bit 2X-Reserved for future use
Bit 10 or 1Profile OngoingA Profile is in progress following a Goal Position(116) instruction update
0 : Profile completed
1 : Profile in progress
Bit 00 or 1In-PositionWhether or not the DYNAMIXEL has arrived to the desired Goal Position(116)
0 : Not arrived
1 : Arrived

Following Error(0x08) and In-Position(0x01) are available when using Position Control Mode, and Extended Position Control Mode.

note

For more details about these operating modes, see [Operating Mode(11)]. NOTE : A Triangular velocity profile is when a configured Rectangular velocity profile cannot reach the configured Profile Velocity(112).

note

NOTE : The In-Position bit will be set when the positional deviation is smaller than a predefined value when in Position related control modes.

Present PWM(124)

This value indicates the present PWM duty being passed to the motor. For more details, please refer to [Goal PWM(100)].

Present Load(126)

Present Load reports an estimate of the current load applied to the motor's output.

UnitValue RangeDescription
0.1%-1,000 ~ 1,000Positive(CCW Load), Negative(CW Load)
note

NOTE : The Present load is an inferred value based on the internal output value; and is not measured using a torque sensor, etc. Therefore, it may be inaccurate for precise measuring of weight or torque. It is recommended to use it only for predicting and monitoring the direction and size of forces being applied to the servo.

Present Velocity(128)

Present Velocity reports the current output speed of the actuator. For more details, please refer to [Goal Velocity(104)].

Present Position(132)

The Present Position(132) indicates the present actuator Position. For more details, see [Goal Position(116)].

Velocity Trajectory(136)

This register stores the current target velocity for the active trajectory created by the current Profile. The specific values and behavior of this register may change based on the active operating mode. For more details, please refer to [Profile Velocity(112)].

  1. Velocity Control Mode : When the generated Profile reaches it's endpoint, [Velocity Trajectory(136)] becomes equal to [Goal Velocity(104)].
  2. Position Control Mode, Extended Position Control Mode : Velocity Trajectory is used to create the [Position Trajectory(140)] used for the movement. When the Profile reaches an endpoint, [Velocity Trajectory(136)] is set to '0'.

Position Trajectory(140)

The Position Trajectory(140) is the desired movement trajectory created by the active Profile.
Position Trajectory(140) is used only when the [Operating Mode(11)] is Position Control Mode, or Extended Position Control Mode
For more details, see What is the Profile.

Present Input Voltage(144)

The Present Input Voltage(144) reports the present voltage level being supplied to the actuator. For more details, see the [Max/Min Voltage Limit(32, 34)].

Present Temperature(146)

The Present Temperature(144) reports the present operating tempurature of the actuator. For more details, see [Temperature Limit (31)].

Backup Ready(147)

The value in this address indicates whether a saved backup of the control table exists in the actuator's memory. For more information see Control Table Backup Packet.

ValueDescription
0There is no saved backup data
1Saved backup data exists.
note

NOTE
Backup Ready is available starting from firmware V45.
See Backup and Restore for more details.

Indirect Address, Indirect Data

The Indirect Address registers allow the assignment of other RAM area control table items to registers in the Indirect Data region. This allows users to map multiple control table items needed for their application to sequential memory addresses to improve Instruction Packet efficiency. If a specific address is allocated an Indirect Address, the corresponding Indirect Data register inherits all the features and properties of the assigned control table address. These properties include Size (Byte length), value range, and Access properties (Read Only, Read/Write). For instance, if 65 (LED) is allocated to Indirect Address 1(168), Indirect Data 1(208) will take on the properties of the [LED(65)] register.

note

NOTE: Only addresses in the RAM area (Address 64 ~ 227) of the control table may be assigned to Indirect Addresses.

Indirect Address RangeDescription
64 ~ 661EEPROM addresses can't be assigned an Indirect Address

Indirect Address and Indirect Data Examples

Example 1 Allocating [LED(65)] to Indirect Data 1(224).

  1. Change the value of Indirect Address 1(168) to '65' which is the address used for LED control.
  2. Set Indirect Data 1(224) to ‘1’, LED(65) also changes to '1' and the LED is turned on.
  3. Set Indirect Data 1(224) to ‘0’, LED(65) also changes to ‘0’ and the LED is turned off.

Example 2 Allocating [Goal Position(116)] to Indirect Data 2(225), 4 sequential bytes have to be allocated.

  1. Indirect Address 2(170) : change the value to '116' which is the first address of Goal Position.
  2. Indirect Address 3(172) : change the value to '117' which is the second address of Goal Position.
  3. Indirect Address 4(174) : change the value to '118' which is the third address of Goal Position.
  4. Indirect Address 5(176) : change the value to '119' which is the fourth address of Goal Position.
  5. Set 4 byte value '1,024' to Indirect Data 2 : [Goal Position(116)] also becomes '1024' and DYNAMIXEL moves.
note

NOTE : In order to allocate Data in the Control Table longer than 2[byte] to Indirect Address, all address must be allocated to Indirect Address like the above Example 2.

note

NOTE : Indirect Address 29 ~ 56 and Indirect Data 29 ~ 56 can only be accessed with [Protocol 2.0].

How to Assemble

Horn Assembly

Idler Horn Assembly

An idler horn is required for installation of hinge frame accessories.

Additionally, the hollow shaft of an installed idler horn provides a neat cable wiring solution.

!HowTo_Idler_Assembly

Frame Assembly

How To Use Spacer Ring

To prevent damage to your frames during assembly, use the included spacer rings to fill the gaps between assembled frames and your DYNAMIXEL case.

!HowTo_SpacerRing

Precaution of Frame and Horn Assembly

warning

WARNING: Before assembling your DYNAMIXEL accessories, ensure that all screws and bolts are the correct length by considering the depth of your DYNAMIXEL’s mounting points. If the length of screw is larger than the depth of the mounting point your frame or DYNAMIXEL may be damaged during assembly.

!Warn_HornAssembly

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

Hinge Frame Assembly

DYNAMIXEL hinge frames are assembled by attaching them to the idler and output horn of your servo.

!Hinge_Assembly

FR12-H101K

!Hinge_Assembly

FR12-H104K

!Hinge_Assembly

FR12-H104K (Back Mount, compatible with DYNAMIXEL XL & XC Series)

!Hinge_Assembly

FR12-H103GM

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

note

NOTE: An idler horn is required for the installation of DYNAMIXEL hinge frames. See the Idler Horn Assembly instructions for more information.

warning

WARNING: During hinge assembly, ensure that all screws are the proper length before installation. See Frame and Horn Assembly Precautions for more information.

Side Frame Assembly

DYNAMIXEL side frames are assembled by attaching them to the mounting points on the sides of your DYNAMIXEL actuator.

!Side_Assembly_Side

FR12-S101K

!Side_Assembly_Bottom

FR12-S102K

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

note

NOTE: Use spacer rings to protect assembled DYNAMIXEL frames. See How To Use Spacer Rings for more information.

Gripper Assembly

!etc_gripper_assembly

FR12-G101GM (FR12-E170 + FR12-E171)

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

note

NOTE: Use spacer rings to protect assembled DYNAMIXEL frames. See How To Use Spacer Rings for more information.

Frame Combination

Hinge and side frames can be combined in a variety of ways to provide complex mounting options.

!Frame_Example

note

NOTE: Find more detailed screw information on frame to frame assembly in the Drawings section.

Custom Frame Assembly

Custom made DYNAMIXEL frames can also be installed by following the instructions below.

Front (Flat Head Screw)

  1. Step 1

    !ETC_FrameAssembly

  2. Step 2

    !ETC_FrameAssembly

note

NOTE: The example frame included in the image is not available for sale.

note

NOTE: Use spacer rings to protect assembled DYNAMIXEL frames see How To Use Spacer Rings for more information.

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

Front (Pan Head Screw)

  1. Step 1

    !ETC_FrameAssembly

  2. Step 2

    !ETC_FrameAssembly

note

NOTE: The example frame included in the image is not available for sale.

note

NOTE: Use spacer rings to protect assembled DYNAMIXEL frames see How To Use Spacer Rings for more information.

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

Side

!ETC_FrameAssembly

warning

WARNING: Before assembling your DYNAMIXEL accessories, ensure that all screws and bolts are the correct length by considering the depth of your DYNAMIXEL’s mounting points. If the length of screw is larger than the depth of the mounting point your frame or DYNAMIXEL may be damaged during assembly.

!3mm_Mount_Deep_Warning

note

NOTE: The example frame included in the image is not available for sale.

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

Bottom

!ETC_FrameAssembly

warning

WARNING: Before assembling your DYNAMIXEL accessories, ensure that all screws and bolts are the correct length by considering the depth of your DYNAMIXEL’s mounting points. If the length of screw is larger than the depth of the mounting point your frame or DYNAMIXEL may be damaged during assembly.

!3mm_Mount_Deep_Warning

note

NOTE: The example frame included in the image is not available for sale.

note

NOTE: Use spacer rings to protect assembled DYNAMIXEL frames see How To Use Spacer Rings for more information.

note

NOTE: Information regarding size and depth of DYNAMIXEL servo mounting points can be found in the Drawings section of the product's eManual page.

Reference

note

NOTE Compatibility Guide
[Harness Compatibility]

What is the Profile

The Profile is a generated movement trajectory intended to reduce vibration, noise and load of the motor by dynamically changing velocity and acceleration during movements. DYNAMIXEL servos provide 3 different types of Profile:

Profiles are usually selected according to the combination of [Profile Velocity(112)] and [Profile Acceleration(108)].

When given a new [Goal Position(116)], the DYNAMIXEL's profile settings creates a desired velocity trajectory based on present movement velocity. When a DYNAMIXEL receives an updated [Goal Position(116)] while it is moving toward the previous [Goal Position(116)], velocity is adjusted smoothly to match the new desired velocity trajectory.
The following explains how the Profile processes [Goal Position(116)] instructions in Position Control mode, and Extended Position Control Mode.

  1. An Instruction from the user is transmitted via the DYNAMIXEL bus, then registered to [Goal Position(116)] (If Velocity-based Profile is selected).
  2. Acceleration time(t1) is calculated based on [Profile Velocity(112)] and [Profile Acceleration(108)].
  3. The type of Profile is decided based on [Profile Velocity(112)], [Profile Acceleration(108)] and total travel distance(ΔPos, the distance difference between desired position and present position).
  4. The selected Profile type is stored at Moving Status(123).
  5. The DYNAMIXEL is driven by the calculated desired trajectory from the Profile.
  6. The desired velocity trajectory and desired position trajectory from the Profile are stored at [Velocity Trajectory(136)] and [Position Trajectory(140)] respectively.
ConditionTypes of Profile
VPRFL(112) = 0Profile not used
(Step Instruction)
(VPRFL(112) ≠ 0) & (APRF(108) = 0)Rectangular Profile
(VPRFL(112) ≠ 0) & (APRF(108) ≠ 0)Trapezoidal Profile

note

NOTE : Velocity Control Mode only uses Profile Acceleration(108). Step and Trapezoidal Profiles are supported. Acceleration time(t1) can be calculated according to the equation below.

Velocity-based Profile : t1 = 64 * {Profile Velocity(112) / Profile Acceleration(108)}
Time-based Profile : t1 = Profile Acceleration(108)

note

NOTE : If Time-based Profile is selected, Profile Velocity(112) is used to set the time span of the Profile(t3), while Profile Acceleration(108) sets allowed accelerating time(t1) in millisecond[ms]. Profile Acceleration(108) will not exceed 50% of the configured Profile Velocity(112) value.

Certifications

Please inquire us for information regarding unlisted certifications.

FCC

note

Note: This equipment has been tested and found to comply with the limits for a Class B digital device, pursuant to part 15 of the FCC Rules. These limits are designed to provide reasonable protection against harmful interference in a residential installation. This equipment generates, uses and can radiate radio frequency energy and, if not installed and used in accordance with the instructions, may cause harmful interference to radio communications. However, there is no guarantee that interference will not occur in a particular installation. If this equipment does cause harmful interference to radio or television reception, which can be determined by turning the equipment off and on, the user is encouraged to try to correct the interference by one more of the following measures:

  • Reorient or relocate the receiving antenna.
  • Increase the separation between the equipment and receiver.
  • Connect the equipment into an outlet on a circuit different from that to which the receiver is connected.
  • Consult the dealer or an experienced radio/TV technician for help.
warning

WARNING
Any changes or modifications not expressly approved by the manufacturer could void the user’s authority to operate the equipment.

Quick Start

Prerequisites

  • DYNAMIXEL Power Supply (12V SMPS, or compatible 12v battery.)

    • See [Compatibility Table]
  • PC with Windows, Linux or MacOS.

  • Serial converter to communicate between your PC and DYNAMIXEL (U2D2, OpenRB-150)

  • DYNAMIXEL Control Software

warning

WARNING:

  • Some software may not support all OS options. Be sure to read the eManual page of any software you wish to use to ensure compatibility.
note

NOTE:

  • The U2D2 is a small size USB to Serial communication converter that enables control and operation of DYNAMIXEL servos directly from a connected PC.
  • The U2D2 Power Hub simplifies the process of connecting an external power source to your U2D2 to supply power to your DYNAMIXEL.

Compatible Software with DYNAMIXEL

DYNAMIXEL Wizard 2.0

[DYNAMIXEL Wizard 2.0] a configuration tool designed to simplify the setup, configuration and management of DYNAMIXEL servos.

The following features are provided by DYNAMIXEL Wizard 2.0:

  • DYNAMIXEL Firmware Update
  • DYNAMIXEL Error Diagnosis
  • DYNAMIXEL Configuration and Testing
  • DYNAMIXEL Real-time Data Plotting
  • Generate & Monitor DYNAMIXEL Packets

DYNAMIXEL SDK

DYNAMIXEL SDK is a software development kit that provides DYNAMIXEL control functions for a variety of popular programming languages.

Supported Programming Laguanges and Features:

  • C, C++, C#, Python, Java, MATLAB, LabVIEW
  • Windows, Mac, Linux.
  • ROS
  • Arduino
note

NOTE: You can also use more variety of software. For more information, see the following to check software provided by ROBOTIS.

  • DYNAMIXEL to software Compatibility Table
  • Controller to software Compatibility Table

Connector Information

ItemTTL
Pinout1 GND
2 VDD
3 DATA
Diagram
Housing
JST EHR-03
PCB Header
JST B3B-EH-A
Crimp TerminalJST SEH-001T-P0.6
Wire Gauge for DYNAMIXEL21 AWG

Communication Circuit

To control the DYNAMIXEL actuators, the main controller needs to convert its UART signals to the half duplex type. The recommended circuit diagram for this is shown below.

TTL Communication

note

NOTE: Above circuit is designed for 5V or 5V tolerant MCU. Otherwise, use a Level Shifter to match the voltage of MCU.

Drawings

XL430-W250 (New)

XL430-W250 (Old)

FR12-H101K

FR12-H104K

FR12-H103GM

FR12-S101K

FR12-S102K

FR12-G101GM

note

NOTE: FR12-G101GM is a gripper frame set that include a FR12-E170 and FR12-E171.

FR12-E170

FR12-E171

Moment Of Inertia