Hello,
I’m now moving these motors (thanks here - OpenCM9.04 and XL-320 motors not working - Hardware Support - ROBOTIS). But I have been unable to update PID gain values using the “writeControlTableItem” function. I’ve tried to set new values and read them back, but it returns 0 for all the PID values (according to the emanual, the default value for POSITION_P_GAIN is 32, but it returns 0 there as well). Anything I’m missing? I’ll post details and code below.
Thanks!
As before, I’m using:
- 2x XL-320 motors
- OpenCM9.04 board, connected to PC via USB
- Arduino IDE v1.8.13
- OpenCM9.04 boards package v1.5.1
- Dynamixel2Arduino library v0.5.1
- no external power supply EDIT 7.4V supplied via bench power supply
Code I’ve been working from:
#include <Dynamixel2Arduino.h>
#define DXL_SERIAL Serial1 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
const uint8_t DXL_DIR_PIN = 28; //OpenCM9.04 EXP Board's DIR PIN. (28 for the DXL port on the OpenCM 9.04 board)
const float DXL_PROTOCOL_VERSION = 2.0;
#define MAX_BAUD 5
const int32_t buad[MAX_BAUD] = {57600, 115200, 1000000, 2000000, 3000000};
#define X_ID 1
#define Y_ID 2
// motors appear to have the center NEAR 512 units but not exactly
#define X_CENTER 520
#define Y_CENTER 526
const float UNITS_PER_DEG = 1024.0/280.0;
// set physical parameters
const float X_ARM_L = 11.0; // mm
const float Y_ARM_L = 16.0; // mm
const float X_MAX = 7.0; // mm
const float X_MIN = -7.0; // mm
const float Y_MAX = 12.0; // mm
const float Y_MIN = -12.0; // mm
const float XY_STEP_SIZE = 2.0 ; // mm
float xTarget = 0.0; // mm, range
float yTarget = 0.0; // mm, range
float xCommand = X_CENTER; // dynamixel step
float yCommand = Y_CENTER; // dynamixel step
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
//This namespace is required to use Control table item names
using namespace ControlTableItem;
void setup() {
// put your setup code here, to run once:
int8_t index = 0;
int8_t found_dynamixel = 0;
// Use UART port of DYNAMIXEL Shield to debug.
Serial.begin(115200); //set debugging port baudrate to 115200bps
while(!Serial); //Wait until the serial port is opened
// // scan for connected motors
// // this can be removed when code is more complete
// for(int8_t protocol = 1; protocol < 3; protocol++) {
// // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
// dxl.setPortProtocolVersion((float)protocol);
// Serial.print("SCAN PROTOCOL ");
// Serial.println(protocol);
//
// for(index = 0; index < MAX_BAUD; index++) {
// // Set Port baudrate.
// Serial.print("SCAN BAUDRATE ");
// Serial.println(buad[index]);
// dxl.begin(buad[index]);
// for(int id = 0; id < DXL_BROADCAST_ID; id++) {
// //iterate until all ID in each buadrate is scanned.
// if(dxl.ping(id)) {
// Serial.print("ID : ");
// Serial.print(id);
// Serial.print(", Model Number: ");
// Serial.println(dxl.getModelNumber(id));
// found_dynamixel++;
// }
// }
// }
// } // end scan routine
// Set Port baudrate to 1Mbps. This has to match with DYNAMIXEL baudrate.
dxl.begin(1000000);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
// Turn off torque when configuring items in EEPROM area
// using position mode for now
dxl.torqueOff(X_ID);
dxl.torqueOff(Y_ID);
dxl.setOperatingMode(X_ID, OP_POSITION);
dxl.setOperatingMode(Y_ID, OP_POSITION);
dxl.torqueOn(X_ID);
dxl.torqueOn(Y_ID);
// Limit the maximum velocity in Position Control Mode. Use 0 for Max speed
dxl.writeControlTableItem(PROFILE_VELOCITY, X_ID, 0);
dxl.writeControlTableItem(PROFILE_VELOCITY, Y_ID, 0);
// mess with PID values
// 27 1 D Gain Derivative Gain RW 0 0 254
// 28 1 I Gain Integral Gain RW 0 0 254
// 29 1 P Gain Proportional Gain RW 32 0 254
dxl.writeControlTableItem(POSITION_P_GAIN, X_ID, 32); delay(500);
dxl.writeControlTableItem(POSITION_I_GAIN, X_ID, 1); delay(500);
dxl.writeControlTableItem(POSITION_D_GAIN, X_ID, 1); delay(500);
// check PID values
Serial.print("XP "); Serial.println(dxl.readControlTableItem(POSITION_P_GAIN, X_ID)); delay(500);
Serial.print("XI "); Serial.println(dxl.readControlTableItem(POSITION_I_GAIN, X_ID)); delay(500);
Serial.print("XD "); Serial.println(dxl.readControlTableItem(POSITION_D_GAIN, X_ID)); delay(500);
Serial.print("YP "); Serial.println(dxl.readControlTableItem(POSITION_P_GAIN, Y_ID)); delay(500);
Serial.print("YI "); Serial.println(dxl.readControlTableItem(POSITION_I_GAIN, Y_ID)); delay(500);
Serial.print("YD "); Serial.println(dxl.readControlTableItem(POSITION_D_GAIN, Y_ID)); delay(500);
Serial.print("X_TORQUE_LIMIT "); Serial.println(dxl.readControlTableItem(TORQUE_LIMIT, X_ID)); delay(500);
Serial.print("Y_TORQUE_LIMIT "); Serial.println(dxl.readControlTableItem(TORQUE_LIMIT, Y_ID)); delay(500);
Serial.print("X_CURRENT_LIMIT "); Serial.println(dxl.readControlTableItem(CURRENT_LIMIT, X_ID)); delay(500);
Serial.print("Y_CURRENT_LIMIT "); Serial.println(dxl.readControlTableItem(CURRENT_LIMIT, Y_ID)); delay(500);
// I think it might need a moment to set the torque on, or something
delay(50);
// move both motors to center positions
dxl.setGoalPosition(X_ID,X_CENTER);
delay(1000); // time to reach position
dxl.setGoalPosition(Y_ID,Y_CENTER);
delay(1000); // time to reach position
}
void loop() {
// print current position
// Serial.print("X pos: "); Serial.print(dxl.getPresentPosition(X_ID)); Serial.print("\t");
// Serial.print("Y pos: "); Serial.print(dxl.getPresentPosition(Y_ID)); Serial.print("\t");
// Serial.print("\n");
// dxl.setGoalPosition(X_ID,X_CENTER + UNITS_PER_DEG*45.0);
// delay(1000);
// dxl.setGoalPosition(X_ID,X_CENTER - UNITS_PER_DEG*45.0);
// delay(1000);
// dxl.setGoalPosition(Y_ID,Y_CENTER + UNITS_PER_DEG*45.0);
// delay(1000);
// dxl.setGoalPosition(Y_ID,Y_CENTER - UNITS_PER_DEG*45.0);
// delay(1000);
// see if user input anything in serial monitor
if (Serial.available() > 0) {
char userInput = Serial.read();
if (userInput == 'a') {
// nudge left (+x)
xTarget += XY_STEP_SIZE;
} else if (userInput == 'd') {
// nudge right (-x)
xTarget -= XY_STEP_SIZE;
} else if (userInput == 'w') {
// nudge forward (+y)
yTarget += XY_STEP_SIZE;
} else if (userInput == 's') {
// nudge backward (-y)
yTarget -= XY_STEP_SIZE;
} else {
Serial.println("Only accepting 'wasd' keyboard input.");
}
while(Serial.available()){Serial.read();} // make sure the buffer is empty
}
// check that values are acceptable
if (xTarget > X_MAX) { xTarget = X_MAX; Serial.println("X_MAX limit."); }
if (xTarget < X_MIN) { xTarget = X_MIN; Serial.println("X_MIN limit."); }
if (yTarget > Y_MAX) { yTarget = Y_MAX; Serial.println("Y_MAX limit."); }
if (yTarget < Y_MIN) { yTarget = Y_MIN; Serial.println("Y_MIN limit."); }
// convert xTarget and yTarget to xCommand (dynamixel unit) and yCommand
xCommand = round( degrees(asin(xTarget/X_ARM_L)) * UNITS_PER_DEG + X_CENTER );
yCommand = round( degrees(asin(yTarget/Y_ARM_L)) * UNITS_PER_DEG + Y_CENTER );
// move
dxl.setGoalPosition(X_ID,xCommand);
delay(100);
dxl.setGoalPosition(Y_ID,yCommand);
delay(100);
Serial.print("Targets (x,y): "); Serial.print(xTarget); Serial.print(", "); Serial.print(yTarget); Serial.print("\t");
Serial.print("Command (x,y): "); Serial.print(xCommand); Serial.print(", "); Serial.print(yCommand); Serial.print("\t");
Serial.print("Current (x,y): "); Serial.print(dxl.getPresentPosition(X_ID)); Serial.print(", "); Serial.println(dxl.getPresentPosition(Y_ID));
// delay(100);
}
And a sample of the output in the following post!