The Dynamixel2Arduino is specifically designed for ROBOTIS providing controller such as OpenCR 1.0 or other supportive controller. But I belive you can make your arduino board as same as long as building the TTL communication properly.
Before starting, I personally recommend testing your board to understand DYNAMIXEL and how to do comm. For the test purpose, when I use no library, but data sending only via UART, I simply made the code as below.
// Make sure this code is only for "Write". If you would like to get feedback from motor, halfduplex rule should be followed.
#include <SoftwareSerial.h>
SoftwareSerial mySerial(4,4); //Data Pin is on PIN 4
void setup(){
mySerial.begin(57600); // Set Baudrate accordingly.
pinMode(4,OUTPUT);
led_on_off(); // Check the Packet right transmitting if you don't get feedback from DYNAMIXEL
delay(10); //Give some interval between packets.
torque_en(); // Torque Enable should be implemented before starting the DYNAMIXEL
}
void torque_en(){
mySerial.write(0xFF); // Header1
mySerial.write(0xFF); // Header2
mySerial.write(0xFD); // Header3
mySerial.write((byte) 0x00); // Header4
mySerial.write(0x01); // ID
mySerial.write(0x06); // Leng(High)
mySerial.write((byte) 0x00); // Leng(Low)
mySerial.write(0x03); // Inst(Write)
mySerial.write(0x40); // Param (Data Address)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0x01); // Param (Data)
mySerial.write(0xDB); // CRC (Low)
mySerial.write(0x66); // CRC (High)
}
void led_on_off(){
mySerial.write(0xFF); // Header1
mySerial.write(0xFF); // Header2
mySerial.write(0xFD); // Header3
mySerial.write((byte) 0x00); // Header4
mySerial.write(0x01); // ID
mySerial.write(0x06); // Leng(High)
mySerial.write((byte) 0x00); // Leng(Low)
mySerial.write(0x03); // Inst(Write)
mySerial.write(0x41); // Param (Data Address)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0x01); // Param (Data)
mySerial.write(0xCC); // CRC (Low)
mySerial.write(0xE6); // CRC (High)
delay(1000);
mySerial.write(0xFF); // Header1
mySerial.write(0xFF); // Header2
mySerial.write(0xFD); // Header3
mySerial.write((byte) 0x00); // Header4
mySerial.write(0x01); // ID
mySerial.write(0x06); // Leng(High)
mySerial.write((byte) 0x00); // Leng(Low)
mySerial.write(0x03); // Inst(Write)
mySerial.write(0x41); // Param (Data Address)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0xC9); // CRC (Low)
mySerial.write(0x66); // CRC (High)
}
void goal_pos_1024(){
mySerial.write(0xFF); // Header1
mySerial.write(0xFF); // Header2
mySerial.write(0xFD); // Header3
mySerial.write((byte) 0x00); // Header4
mySerial.write(0x01); // ID
mySerial.write(0x09); // Leng(High)
mySerial.write((byte) 0x00); // Leng(Low)
mySerial.write(0x03); // Inst(Write)
mySerial.write(0x74); // Param (Data Address)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0x04); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0xB2); // CRC (Low)
mySerial.write(0x89); // CRC (High)
}
void goal_pos_2048(){
mySerial.write(0xFF); // Header1
mySerial.write(0xFF); // Header2
mySerial.write(0xFD); // Header3
mySerial.write((byte) 0x00); // Header4
mySerial.write(0x01); // ID
mySerial.write(0x09); // Leng(High)
mySerial.write((byte) 0x00); // Leng(Low)
mySerial.write(0x03); // Inst(Write)
mySerial.write(0x74); // Param (Data Address)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0x08); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write((byte) 0x00); // Param (Data)
mySerial.write(0x42); // CRC (Low)
mySerial.write(0x89); // CRC (High)
}
void loop(){
delay(750); // Give it a time while pysically moving.
goal_pos_1024(); // Move 1024 (90 deg)
delay(750); // Give it a time while pysically moving.
goal_pos_2048(); // Move 1024 (180 deg)
}
My setup as following:
- Digital Pin 4 is assigned as a software serial pins instead of using 0,1

- I highly recommend using hardware serial pins (0,1) as you can perform quicker packet transmission and higher baudrates support (thanks to UART converter built in a chip)
Note that you can not get feedback from DYNAMIXEL by this setup. DYNAMIXEL should communicate with its master device under the Half-Duplex rule (While TX pin is under control, RX pin must wait until TX is done), therefore you should build the buffer enable (Triple State buffer) as below (or do it programmatically using software serial library. Some of the users have achieved it).
