You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am currently trying to control a Poppy Ergo Jr arm, which uses 6 XL-320 servos, using an OpenCM9.04 C-Type.
Everything works fine when the robot is powered up, but after a few movements, the servos stop moving but the goal position is set and is different from the current position.
Also, when one servo stops working, it of course cripples the entire arm.
Please find below the full code. Also, if you want to replicate the issue, sending the command set_motor <id> <angle in degrees> via serial allows you to move the servos.
#include<Dynamixel2Arduino.h>
#defineDXL_SERIAL Serial1
#defineDEBUG_SERIAL Serial
#defineMOTOR_BAUDRATE1000000// XL-320 baudrate
#defineDXL_DIR_PIN28// OpenCM 9.04 DYNAMIXEL TTL Bus
#defineDXL_PROTOCOL_VERSION2.0
#defineANGLE_TOLERANCE0.5
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
structMotor
{
int id;
int position;
};
// This namespace is required to use Control table item namesusingnamespaceControlTableItem;voidsetup()
{
// Use UART port of DYNAMIXEL Shield to debug.
DEBUG_SERIAL.begin(115200);
while (!DEBUG_SERIAL)
;
dxl.begin(MOTOR_BAUDRATE);
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
for (int i = 1; i <= 6; i++)
{
// Get DYNAMIXEL information
dxl.ping(i);
// Turn off torque when configuring items in EEPROM area
dxl.torqueOff(i);
dxl.setOperatingMode(i, OP_POSITION);
dxl.torqueOn(i);
// Limit the maximum velocity in Position Control Mode. Use 0 for Max speed
dxl.writeControlTableItem(PROFILE_VELOCITY, i, 0);
}
DEBUG_SERIAL.println("ready");
}
/** * @brief Sets The goal position of a motor. * * @param motor The Motor struct representing the motor to set the position for.*/void_set_motor(Motor &motor)
{
float f_present_position = dxl.getPresentPosition(motor.id, UNIT_DEGREE);
if (abs(f_present_position - motor.position) < ANGLE_TOLERANCE)
{
#ifdef DEBUG
DEBUG_SERIAL.println("Too close");
#endifreturn;
}
int success = dxl.setGoalPosition(motor.id, motor.position, UNIT_DEGREE);
if (success != 1)
{
#ifdef DEBUG
DEBUG_SERIAL.print("Failed to set goal position for motor ");
DEBUG_SERIAL.println(dxl.getLastLibErrCode());
#endifreturn;
}
// Wait for the motor to reach the goal positiondo
{
f_present_position = dxl.getPresentPosition(motor.id, UNIT_DEGREE);
#ifdef DEBUG
DEBUG_SERIAL.print("Motor ");
DEBUG_SERIAL.print(motor.id);
DEBUG_SERIAL.print(" is at position ");
DEBUG_SERIAL.print(f_present_position);
DEBUG_SERIAL.print(". Goal position for motor ");
DEBUG_SERIAL.print(motor.id);
DEBUG_SERIAL.print(" is ");
DEBUG_SERIAL.println(motor.position);
DEBUG_SERIAL.print("Present current: ");
DEBUG_SERIAL.print(dxl.getPresentCurrent(motor.id));
DEBUG_SERIAL.print(" Goal current: ");
DEBUG_SERIAL.println(dxl.readControlTableItem(GOAL_CURRENT, motor.id));
#endif
} while (abs(f_present_position - motor.position) > ANGLE_TOLERANCE);
}
/** * @brief Split a string into an array of strings based on a delimiter * * @param input The string to split * @param delimiter The delimiter to split the string on * @param output The array of strings to store the split string in * @param max_items The maximum number of items to split the string into * @return int The number of items the string was split into*/intsplit_string(String input, char delimiter, String *output, int max_items)
{
int item_count = 0;
int start_index = 0;
int end_index = input.indexOf(delimiter, start_index);
while (end_index >= 0 && item_count < max_items)
{
// Skip the first element in the output arrayif (item_count > 0)
output[item_count - 1] = input.substring(start_index, end_index);
item_count++;
start_index = end_index + 1;
end_index = input.indexOf(delimiter, start_index);
}
if (start_index < input.length() && item_count < max_items)
{
output[item_count - 1] = input.substring(start_index);
item_count++;
}
return item_count - 1; // Return item_count - 1 to account for skipping the first element
}
/** * @brief Process the set_motor message * * @param message The message to process*/intprocess_set_motor_message(String message, Motor *motors)
{
String arguments[12] = {};
int num_arguments = split_string(message, '', arguments, 12);
#ifdef DEBUG
DEBUG_SERIAL.print("Number of arguments: ");
DEBUG_SERIAL.println(num_arguments);
for (unsignedint i = 0; i < num_arguments; i++)
{
DEBUG_SERIAL.print("Argument ");
DEBUG_SERIAL.print(i);
DEBUG_SERIAL.print(": ");
DEBUG_SERIAL.println(arguments[i]);
}
#endifif (num_arguments % 2 != 0)
{
#ifdef DEBUG
DEBUG_SERIAL.println("Invalid number of arguments");
#endifreturn -1;
}
unsignedint motor_index = 0;
for (unsignedint argument_index = 0; argument_index < num_arguments; argument_index++)
{
if (argument_index % 2 == 0) // If even, it is the motor ID
{
motors[motor_index].id = arguments[argument_index].toInt();
}
else
{
motors[motor_index].position = arguments[argument_index].toInt();
// Avoid blocking the program if the position is out of rangeif (motors[motor_index].position < 0 || motors[motor_index].position > 296)
{
motors[motor_index].position = 0;
}
motor_index++;
}
}
return num_arguments / 2;
}
voidloop()
{
if (DEBUG_SERIAL.available() > 0)
{
String message = DEBUG_SERIAL.readStringUntil('\n');
message.trim();
if (message.startsWith("set_motor"))
{
Motor motors[6] = {};
int number_motors = process_set_motor_message(message, motors);
if (number_motors < 0)
{
#ifdef DEBUG
DEBUG_SERIAL.println("Invalid message");
#endifreturn;
}
for (unsignedint motor_index; motor_index < number_motors; motor_index++)
{
#ifdef DEBUG
// Print the extracted values
DEBUG_SERIAL.print("Motor ID: ");
DEBUG_SERIAL.println(motors[motor_index].id);
DEBUG_SERIAL.print("Motor Position: ");
DEBUG_SERIAL.println(motors[motor_index].position);
#endif_set_motor(motors[motor_index]);
}
}
}
}
The text was updated successfully, but these errors were encountered:
Hi,
I am currently trying to control a Poppy Ergo Jr arm, which uses 6 XL-320 servos, using an OpenCM9.04 C-Type.
Everything works fine when the robot is powered up, but after a few movements, the servos stop moving but the goal position is set and is different from the current position.
Also, when one servo stops working, it of course cripples the entire arm.
Please find below the full code. Also, if you want to replicate the issue, sending the command
set_motor <id> <angle in degrees>
via serial allows you to move the servos.The text was updated successfully, but these errors were encountered: