A simple C++ API for controlling dynamixel XM430-* servomotor. The API was made in order to control a robotic arm, and consist of an unique class. The programme ran on a Raspberry PI 3B+, with the Dynamixel XM430 motors connected with U2D2 (Serial-RS485). The datasheet references can be found HERE.
Lastest Update: Switch from Velocity to timed driving mode. This give the capacity to set dead line of the motors movement. If you still want to use a constant velocity instead, please let me know. SetProfile was replace by SetTimeProfile(ta, tf), see API description.
The programme depend on the dynamixel_sdk library. Installation information can be found on their github. Please install the proper library depending on your platform.
Once the install is done, download this repository and make the MakeFile in the make_run directory, an run the code ./exampleServo
On Ubuntu, we may need to run sudo chmod a+rw /dev/ttyUSB*.
You can add your own code to the project by adding: SOURCES += yourcode.cpp in the MakeFile
If you encounter any problem with the installation let me know. If when running the code a Hardware Error type pop ups, it maybe cause by a power supply too important (12V are recommended).
The API is illustrated in the exampleServo.cpp file.
//Create a servo motor: servo*(dynamyxel ID, mode, currentlimit, goalcurrent)
MotorXM430 servo1(1, 3, 800, 90);
//Accessing the motors function:
servo1.PrintOperatingMode();
//Controlling the motor:
servo1.TorqueON();
servo1.Goto(180);
usleep(500000);
printf("Motor %d, current position: %f\n",servo1.GetID(), servo1.ReadAngle());
//Adding another motor:
MotorXM430 servo2(2, 3, 800, 90);
printf("Motor %d, current position: %f\n",servo2.GetID(), servo2.ReadAngle());
Output of the program:
-
int GetID();
GetID: return the motors ID. Input: Void. Output : int ID. Example: MotorXM430 motor; printf("ID: %d\n",motor.GetID()); -
uint16_t GetModelNumber();
GetModelNumber(): return the model of the motor. (ex: model numer 1020 is the MX430). This function is used to read the current of the motors. As the first function call in the construstor, we used this function to check if the motor is turn ON or without failure. In case of failure, this function will terminate the program. -
uint8_t IsMoving();
IsMoving(): return the moving status of the motor.Used for motor synchronisation when several motors are moving. -
void MovingStatus();
MovingStatus: printf the moving status of the motors. Used for debugging. -
int16_t ReadCurrent();
ReadCurrent(): return the signed current of the motor in mA. -
float MAP(uint32_t angle, long in_min, long in_max, long out_min, long out_max);
MAP: return the mapped angle value into the other unit. Used for converting angle degree to angle motors.]
Inputs: angle is the value we want to convert. in_min/max: the minimal/maximal angle value in the 1fst unit. out_min/max: the minimal/maximal angle value in the 2nd unit.
Output: the mapped angle.
Example: MAP(m_present_position, MIN_MOTOR_ANGLE, MAX_MOTOR_ANGLE, 0.0, 360.0) -
void TorqueON();
TorqueON: activate the torque inside the motor. Without torque the motor will not move. -
void TorqueOFF();
TorqueOFF: disactivate the torque inside the motor. Without torque the motor will not move. -
float ReadAngle();
ReadAngle: return the current angle of the motor in degree -
void Goto(float position);
Goto: set the goal position in the motor. The function do not currently check the validity of the input
Input: wanted position in degree float -
void SetOperatingMode(uint8_t mode);
SetOperatingMode: set the operating mode in the motor (Availiable mode: 0 (Current), 1 (Velocity), 3 (Position), 4 (Extended position), 5 (current-based position), 16 (PWM))
Input: wanted mode uint8_t -
void PrintOperatingMode();
PrintOperationMode: printf in the console the operationmode. Used for debugging. -
void SetPID(uint16_t P_gain, uint16_t I_gain, uint16_t D_gain);
SetPID: set the different parameters of the internal motor's PID controler.
Input: the P / I / D value between 0-16383 uint16_t -
void PrintPID();
PrintPID: printf the gain value of the motor's PID in the consol. Used for debugging. -
void SetFFGain(uint16_t FF1Gain, uint16_t FF2Gain);
SetFFGain: set the different parameters of the internal motor's FeedForward controler.
Input: the FF1 FF2 value between 0-16383 uint16_t -
void PrintFFGain();
PrintFFGain: printf the gain value of the motor's FeedForward control in the consol. Used for debugging. -
void SetCurrentLimit();
SetCurrentLimit: set the maximun current (torque) output of the motor. Used for current-based position control (gripper)
Input: is set in the define section CURRENT_LIMIT 1193 -
void PrintCurrentLimit();
PrintCurrentLimit: printf the value of the current limit (mA) in the console. Used for debugging. -
void SetGoalCurrent(uint16_t GoalCurrent);
SetGoalCurrent: set the goal current. Used for current-based position control
Input: wanted goal current mA uint16_t. The function check if the wanted goalcurrent is not exceeding the currentlimit -
void PrintGoalCurrent();
PrintGoalcurrent: printf the value of the goalcurrent (mA) in the console. Used for debugging. -
void SetDrivingMode(uint8_t type);
SetDriving: set the driving mode of the motor, between TIMED_BASED and VELOCITY_BASED driving mode.
Input: driving mode input (0: Velocity / 4: Time) -
uint8_t PrintDrivingMode();
PrintDrivingMode: print and return the current driving mode of the motor -
void SetTimeProfile(uint32_t Ta, uint32_t Tf);
SetTimeProfile: set the acceleration profile of the motor. Ta is the acceleration time, and tf is the final time.
Input: Ta, Tf in ms. If Ta = 0, the profile is rectangle / if Ta=0.5Tf, the profile is triangle. Please refer to Dynamixel documentation for more information -
void PrintTimeProfile();
PrintTimeProfile: print the current Ta and Tf profile parameter of the motor