C Sync Write Protocol 1.0
-
Description
This example writes Goal Positions to two DYNAMIXEL’s simultaneously and reads their Present Positions until they stop moving. The funtions that are related with the Syncwrite handle the number of items that are near to each other in the Dynamixel control table on multiple DYNAMIXEL’s, such as the goal position and the goal velocity.
-
Supported DYNAMIXEL
Protocol 1.0 DYNAMIXEL
Sample code
/*
* sync_write.c
*
* Created on: 2016. 5. 16.
* Author: Leon Ryu Woon Jung
*/
//
// ********* Sync Write Example *********
//
//
// Available Dynamixel model on this example : All models using Protocol 1.0
// This example is designed for using two Dynamixel MX-28, and an USB2DYNAMIXEL.
// To use another Dynamixel model, such as X series, see their details in E-Manual(support.robotis.com) and edit below "#define"d variables yourself.
// Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000 [1M])
//
#ifdef __linux__
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#elif defined(_WIN32) || defined(_WIN64)
#include <conio.h>
#endif
#include <stdlib.h>
#include <stdio.h>
#include "dynamixel_sdk.h" // Uses DYNAMIXEL SDK library
// Control table address
#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model
#define ADDR_MX_GOAL_POSITION 30
#define ADDR_MX_PRESENT_POSITION 36
// Data Byte Length
#define LEN_MX_GOAL_POSITION 2
#define LEN_MX_PRESENT_POSITION 2
// Protocol version
#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel
// Default setting
#define DXL1_ID 1 // Dynamixel#1 ID: 1
#define DXL2_ID 2 // Dynamixel#2 ID: 2
#define BAUDRATE 1000000
#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller
// ex) Windows: "COM1" Linux: "/dev/ttyUSB0"
#define TORQUE_ENABLE 1 // Value for enabling the torque
#define TORQUE_DISABLE 0 // Value for disabling the torque
#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value
#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.)
#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold
#define ESC_ASCII_VALUE 0x1b
int getch()
{
#ifdef __linux__
struct termios oldt, newt;
int ch;
tcgetattr(STDIN_FILENO, &oldt);
newt = oldt;
newt.c_lflag &= ~(ICANON | ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &newt);
ch = getchar();
tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
return ch;
#elif defined(_WIN32) || defined(_WIN64)
return _getch();
#endif
}
int kbhit(void)
{
#ifdef __linux__
struct termios oldt, newt;
int ch;
int oldf;
tcgetattr(STDIN_FILENO, &oldt);
newt = oldt;
newt.c_lflag &= ~(ICANON | ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &newt);
oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
ch = getchar();
tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
fcntl(STDIN_FILENO, F_SETFL, oldf);
if (ch != EOF)
{
ungetc(ch, stdin);
return 1;
}
return 0;
#elif defined(_WIN32) || defined(_WIN64)
return _kbhit();
#endif
}
int main()
{
// Initialize PortHandler Structs
// Set the port path
// Get methods and members of PortHandlerLinux or PortHandlerWindows
int port_num = portHandler(DEVICENAME);
// Initialize PacketHandler Structs
packetHandler();
// Initialize Groupsyncwrite instance
int group_num = groupSyncWrite(port_num, PROTOCOL_VERSION, ADDR_MX_GOAL_POSITION, LEN_MX_GOAL_POSITION);
int index = 0;
int dxl_comm_result = COMM_TX_FAIL; // Communication result
uint8_t dxl_addparam_result = False; // AddParam result
int dxl_goal_position[2] = { DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE }; // Goal position
uint8_t dxl_error = 0; // Dynamixel error
uint16_t dxl1_present_position = 0, dxl2_present_position = 0; // Present position
// Open port
if (openPort(port_num))
{
printf("Succeeded to open the port!\n");
}
else
{
printf("Failed to open the port!\n");
printf("Press any key to terminate...\n");
getch();
return 0;
}
// Set port baudrate
if (setBaudRate(port_num, BAUDRATE))
{
printf("Succeeded to change the baudrate!\n");
}
else
{
printf("Failed to change the baudrate!\n");
printf("Press any key to terminate...\n");
getch();
return 0;
}
// Enable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL1_ID);
}
// Enable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL2_ID);
}
while (1)
{
printf("Press any key to continue! (or press ESC to quit!)\n");
if (getch() == ESC_ASCII_VALUE)
break;
// Add Dynamixel#1 goal position value to the Syncwrite storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL1_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID);
return 0;
}
// Add Dynamixel#2 goal position value to the Syncwrite parameter storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL2_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID);
return 0;
}
// Syncwrite goal position
groupSyncWriteTxPacket(group_num);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
// Clear syncwrite parameter storage
groupSyncWriteClearParam(group_num);
do
{
// Read Dynamixel#1 present position
dxl1_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Read Dynamixel#2 present position
dxl2_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position);
} while ((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD));
// Change goal position
if (index == 0)
{
index = 1;
}
else
{
index = 0;
}
}
// Disable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Disable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Close port
closePort(port_num);
return 0;
}
Details
#ifdef __linux__
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#elif defined(_WIN32) || defined(_WIN64)
#include <conio.h>
#endif
This source includes above to get key input interruption while the example is running. Actual functions for getting the input is described in a little below.
#include <stdlib.h>
The function abs()
is in the example code, and it needs stdlib.h
to be included.
#include <stdio.h>
The example shows Dynamixel status in sequence by the function printf()
. So here stdio.h
is needed.
#include "dynamixel_sdk.h" // Uses DYNAMIXEL SDK library
All libraries of DYNAMIXEL SDK are linked with the header file dynamixel_sdk.h
.
// Control table address
#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model
#define ADDR_MX_GOAL_POSITION 30
#define ADDR_MX_PRESENT_POSITION 36
// Data Byte Length
#define LEN_MX_GOAL_POSITION 2
#define LEN_MX_PRESENT_POSITION 2
Dynamixel series have their own control tables: Addresses and Byte Length in each items. To control one of the items, its address (and length if necessary) is required. Find your requirements in http://emanual.robotis.com/.
// Protocol version
#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel
Dynamixel uses either or both protocols: Protocol 1.0 and Protocol 2.0. Choose one of the Protocol which is appropriate in the Dynamixel.
// Default setting
#define DXL1_ID 1 // Dynamixel#1 ID: 1
#define DXL2_ID 2 // Dynamixel#2 ID: 2
#define BAUDRATE 1000000
#define DEVICENAME1 "/dev/ttyUSB0" // Check which port is being used on your controller
#define TORQUE_ENABLE 1 // Value for enabling the torque
#define TORQUE_DISABLE 0 // Value for disabling the torque
#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value
#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.)
#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold
#define ESC_ASCII_VALUE 0x1b
Here we set some variables to let you freely change them and use them to run the example code.
As the document previously said in previous chapter, customize Dynamixel control table items, such as DXL_ID
number, communication BAUDRATE
, and the DEVICENAME
, on your own terms of needs. In particular, BAUDRATE
and DEVICENAME
have systematical dependencies on your controller, so make clear what kind of communication method you will use.
The example uses two DYNAMIXEL’s DXL1_ID
, DXL2_ID
connected with the port DEVICENAME
.
Dynamixel basically needs the TORQUE_ENABLE
to be rotating or give you its internal information. On the other hand, it doesn’t need torque enabled if you get your goal, so finally do TORQUE_DISABLE
to prepare to the next sequence.
Since the Dynamixel has its own rotation range, it may shows malfunction if your request on your dynamixel is out of range. For example, Dynamixel MX-28 and Dynamixel PRO 54-200 has its rotatable range as 0 ~ 4028 and -250950 ~ 250950, each.
DXL_MOVING_STATUS_THRESHOLD
acts as a criteria for verifying its rotation stopped.
int getch()
{
#ifdef __linux__
struct termios oldt, newt;
int ch;
tcgetattr(STDIN_FILENO, &oldt);
newt = oldt;
newt.c_lflag &= ~(ICANON | ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &newt);
ch = getchar();
tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
return ch;
#elif defined(_WIN32) || defined(_WIN64)
return _getch();
#endif
}
int kbhit(void)
{
#ifdef __linux__
struct termios oldt, newt;
int ch;
int oldf;
tcgetattr(STDIN_FILENO, &oldt);
newt = oldt;
newt.c_lflag &= ~(ICANON | ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &newt);
oldf = fcntl(STDIN_FILENO, F_GETFL, 0);
fcntl(STDIN_FILENO, F_SETFL, oldf | O_NONBLOCK);
ch = getchar();
tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
fcntl(STDIN_FILENO, F_SETFL, oldf);
if (ch != EOF)
{
ungetc(ch, stdin);
return 1;
}
return 0;
#elif defined(_WIN32) || defined(_WIN64)
return _kbhit();
#endif
}
These functions accept the key inputs in terms of example action. The example codes mainly apply the function getch()
rather than the function kbhit()
to get information which key has been pressed.
int main()
{
// Initialize PortHandler Structs
// Set the port path
// Get methods and members of PortHandlerLinux or PortHandlerWindows
int port_num = portHandler(DEVICENAME);
// Initialize PacketHandler Structs
packetHandler();
// Initialize Groupsyncwrite instance
int group_num = groupSyncWrite(port_num, PROTOCOL_VERSION, ADDR_MX_GOAL_POSITION, LEN_MX_GOAL_POSITION);
int index = 0;
int dxl_comm_result = COMM_TX_FAIL; // Communication result
uint8_t dxl_addparam_result = False; // AddParam result
int dxl_goal_position[2] = { DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE }; // Goal position
uint8_t dxl_error = 0; // Dynamixel error
uint16_t dxl1_present_position = 0, dxl2_present_position = 0; // Present position
// Open port
if (openPort(port_num))
{
printf("Succeeded to open the port!\n");
}
else
{
printf("Failed to open the port!\n");
printf("Press any key to terminate...\n");
getch();
return 0;
}
// Set port baudrate
if (setBaudRate(port_num, BAUDRATE))
{
printf("Succeeded to change the baudrate!\n");
}
else
{
printf("Failed to change the baudrate!\n");
printf("Press any key to terminate...\n");
getch();
return 0;
}
// Enable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL1_ID);
}
// Enable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL2_ID);
}
while (1)
{
printf("Press any key to continue! (or press ESC to quit!)\n");
if (getch() == ESC_ASCII_VALUE)
break;
// Add Dynamixel#1 goal position value to the Syncwrite storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL1_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID);
return 0;
}
// Add Dynamixel#2 goal position value to the Syncwrite parameter storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL2_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID);
return 0;
}
// Syncwrite goal position
groupSyncWriteTxPacket(group_num);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
// Clear syncwrite parameter storage
groupSyncWriteClearParam(group_num);
do
{
// Read Dynamixel#1 present position
dxl1_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Read Dynamixel#2 present position
dxl2_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position);
} while ((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD));
// Change goal position
if (index == 0)
{
index = 1;
}
else
{
index = 0;
}
}
// Disable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Disable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Close port
closePort(port_num);
return 0;
}
In main()
function, the codes call actual functions for Dynamixel control.
// Initialize PortHandler Structs
// Set the port path
// Get methods and members of PortHandlerLinux or PortHandlerWindows
int port_num = portHandler(DEVICENAME);
portHandler()
function sets port path as DEVICENAME
and get port_num
, and prepares an appropriate functions for port control in controller OS automatically. port_num
would be used in many functions in the body of the code to specify the port for use.
// Initialize PacketHandler Structs
packetHandler();
packetHandler()
function initializes parameters used for packet construction and packet storing.
// Initialize Groupsyncwrite instance
int group_num = groupSyncWrite(port_num, PROTOCOL_VERSION, ADDR_MX_GOAL_POSITION, LEN_MX_GOAL_POSITION);
groupSyncWrite()
function initializes grouped parameters used for packet construction and packet storing. The utility functions of sync write deals simultaneously with more than one Dynamixel through #port_num
port, building packets by the function which uses PROTOCOL_VERSION
, and writing LEN_MX_GOAL_POSITION
bytes of the values on the address ADDR_MX_GOAL_POSITION
.
int index = 0;
int dxl_comm_result = COMM_TX_FAIL; // Communication result
bool dxl_addparam_result = false; // AddParam result
int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position
uint8_t dxl_error = 0; // Dynamixel error
uint16_t dxl1_present_position = 0, dxl2_present_position = 0; // Present position
index
variable points the direction to where the Dynamixel should be rotated.
dxl_comm_result
indicates which error has been occurred during packet communication.
dxl_addparam_result
indicates the result of parameter addition used for sync/bulk related functions
dxl_goal_position
stores goal points of Dynamixel rotation.
dxl_error
shows the internal error in Dynamixel.
dxl1_present_position
and dxl2_present_position
view where now each Dynamixel points out.
// Open port
if (openPort(port_num))
{
printf("Succeeded to open the port!\n");
}
else
{
printf("Failed to open the port!\n");
printf("Press any key to terminate...\n");
_getch();
return 0;
}
First, controller opens #port_num
port to do serial communication with the Dynamixel. If it fails to open the port, the example will be terminated.
// Set port baudrate
if (setBaudRate(port_num, BAUDRATE))
{
printf("Succeeded to change the baudrate!\n");
}
else
{
printf("Failed to change the baudrate!\n");
printf("Press any key to terminate...\n");
_getch();
return 0;
}
Secondly, the controller sets the communication BAUDRATE
at #port_num
port opened previously.
// Enable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL1_ID);
}
// Enable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
else
{
printf("Dynamixel#%d has been successfully connected \n", DXL2_ID);
}
As mentioned in the document, above code enables each Dynamixel`s torque to set their status as being ready to move.
write1ByteTxRx()
function sends an instruction to the #DXL1_ID
and #DXL2_ID
DYNAMIXEL in PROTOCOL_VERSION
communication protocol through #port_num
port, writing 1 byte of TORQUE_ENABLE
value to ADDR_MX_TORQUE_ENABLE
address. The function checks Tx/Rx result and receives Hardware error.
getLastTxRxResult()
function and getLastRxPacketError()
function get either, and then printTxRxResult()
function and printRxPacketError()
function show results on the console window if any communication error or Hardware error has been occurred.
while (1)
{
printf("Press any key to continue! (or press ESC to quit!)\n");
if (getch() == ESC_ASCII_VALUE)
break;
// Add Dynamixel#1 goal position value to the Syncwrite storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL1_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID);
return 0;
}
// Add Dynamixel#2 goal position value to the Syncwrite parameter storage
dxl_addparam_result = groupSyncWriteAddParam(group_num, DXL2_ID, dxl_goal_position[index], LEN_MX_GOAL_POSITION);
if (dxl_addparam_result != True)
{
fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID);
return 0;
}
// Syncwrite goal position
groupSyncWriteTxPacket(group_num);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
// Clear syncwrite parameter storage
groupSyncWriteClearParam(group_num);
do
{
// Read Dynamixel#1 present position
dxl1_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Read Dynamixel#2 present position
dxl2_present_position = read2ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_PRESENT_POSITION);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position);
} while ((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD));
// Change goal position
if (index == 0)
{
index = 1;
}
else
{
index = 0;
}
}
During while()
loop, the controller writes and reads each Dynamixel position through packet transmission/reception(Tx/Rx).
To continue their rotation, press any key except ESC.
groupSyncWriteAddParam()
function stores the Dynamixel ID and its LEN_MX_GOAL_POSITION
bytes goal position dxl_goal_position
to the syncwrite target Dynamixel list.
groupSyncWriteTxPacket()
function sends an instruction to the Dynamixel #DXL1_ID
and #DXL2_ID
at the same time through #port_num
, making it possible to write same pre-listed length bytes to same pre-listed address. The function checks Tx/Rx result.
getLastTxRxResult()
function gets it, and then printTxRxResult()
function shows result on the console window if any communication error has been occurred.
groupSyncWriteClearParam()
function clears the Dynamixel list of groupsyncwrite.
read2ByteTxRx()
function sends an instruction to the #DXL1_ID
and #DXL2_ID
DYNAMIXEL in PROTOCOL_VERSION
communication protocol through #port_num
port, requesting 2 bytes of value in ADDR_MX_PRESENT_POSITION
address. The function checks Tx/Rx result and receives Hardware error.
getLastTxRxResult()
function and getLastRxPacketError()
function get either, and then printTxRxResult()
function and printRxPacketError()
function show results on the console window if any communication error or Hardware error has been occurred.
Reading their present position will be ended when absolute value of (dxl_goal_position[index] - dxl1_present_position)
or (dxl_goal_position[index] - dxl2_present_position)
becomes smaller then DXL_MOVING_STATUS_THRESHOLD
.
At last, it changes their direction to the counter-wise and waits for extra key input.
// Disable Dynamixel#1 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
// Disable Dynamixel#2 Torque
write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE);
if ((dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION)) != COMM_SUCCESS)
{
printTxRxResult(PROTOCOL_VERSION, dxl_comm_result);
}
else if ((dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION)) != 0)
{
printRxPacketError(PROTOCOL_VERSION, dxl_error);
}
The controller frees the DYNAMIXEL to be idle.
write1ByteTxRx()
function sends an instruction to the #DXL1_ID
and #DXL2_ID
DYNAMIXEL in PROTOCOL_VERSION
communication protocol through #port_num
port, writing 1 byte of TORQUE_DISABLE
value to ADDR_MX_TORQUE_ENABLE
address. The function checks Tx/Rx result and receives Hardware error.
getLastTxRxResult()
function and getLastRxPacketError()
function get either, and then printTxRxResult()
function and printRxPacketError()
function show results on the console window if any communication error or Hardware error has been occurred.
// Close port
closePort(port_num);
return 0;
Finally, port becomes disposed.