Closed Danaish-Rathore closed 3 years ago
Hi @Danaish-Rathore
Under the (Extended) Position Control mode of Protocol 2.0, Max velocity and acceleration is managed by the Profile Velocity(112) and the Profile Acceleration(108) instead of Goal Velocity(104).
You may use the writeControlTableItem() as below:
dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, 100); // Limit the max velocity to 100 (*0.229 RPM)
dxl.writeControlTableItem(PROFILE_ACCELERATION, DXL_ID, 10); // Limit the max accel / decel to 10 (*214.577rev/min^2)
Thank you.
@Danaish-Rathore I've transferred this issue to the relevant repository. Thanks!
@ROBOTIS-Will
Again many thanks. Actually I tried the profile velocity yesterday night and it worked but I couldn't update here.
@Danaish-Rathore Oh, I see. Glad that the Profile Velocity works for you. Not sure why the transferred thread cannot be updated by the original author, but thanks for the updates! :)
@ROBOTIS-Will The profile velocity only works for protocol (2.0) and it doesn't work for MX-28T protocol (1.0). Therefore, for version (1.0) the goal velocity can be used with extended position control mode as I tried. Thanks
@Danaish-Rathore The MX-28T with Protocol 1.0 does not have Profile Velocity / Acceleration address. In case of using Protocol 1.0 for MX series, you can control the max velocity with the Moving Speed(32).
dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, 100);
@ROBOTIS-Will
Oh! that is nice. Next time I will try with this and again many thanks.
ISSUE TEMPLATE ver. 1.2.0
Please fill this template for more accurate and prompt support.
Which DYNAMIXEL SDK version do you use?
3.4.1
Which programming language/tool do you use? Arduino
Which operating system do you use? Windows 10
Which USB serial converter do you use? Arduino Uno
Which DYNAMIXEL do you use? MX-28T(2.0)
Have you searched the issue from the closed issue threads?
Please describe the issue in detail
Hi everyone,
I am controlling MX servos using Arduino Uno and working on the Extended position control mode, now the problem is I don't know how to set the velocity limit/control velocity for MX servo protocol (2.0) under extended position control mode. However, I have tried with the below code and it seems the code is working and the velocity is controlled only for protocol (1.0) .
`void setup() {
DEBUG_SERIAL.begin(115200); dxl.begin(57600); dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION); dxl.ping(DXL_ID);
// Turn off torque when configuring items in EEPROM area dxl.torqueOff(DXL_ID); dxl.setOperatingMode(DXL_ID, OP_VELOCITY); dxl.torqueOn(DXL_ID);
//Set Goal Velocity using RPM dxl.setGoalVelocity(DXL_ID, 20, UNIT_RPM); delay(100);
DEBUG_SERIAL.print("Present Velocity(rpm) : "); DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID, UNIT_RPM)); delay(1000);
}
void loop() {
// Extended Position Control Mode in protocol2.0, //dxl.torqueOff(DXL_ID); dxl.setOperatingMode(DXL_ID, OP_EXTENDED_POSITION); dxl.torqueOn(DXL_ID); if(dxl.setGoalPosition(DXL_ID, 0)){ delay(5000); DEBUG_SERIAL.print("Present Extended Position1 : "); DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID)); DEBUG_SERIAL.println(); } // Extended Position Contorl Mode in protocol2.0, //dxl.torqueOff(DXL_ID); dxl.setOperatingMode(DXL_ID, OP_EXTENDED_POSITION); dxl.torqueOn(DXL_ID); if(dxl.setGoalPosition(DXL_ID, 5000)){ delay(5000); DEBUG_SERIAL.print("Present Extended Position2 : "); DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID)); DEBUG_SERIAL.println(); } }`
The code can control the extended position and velocity of servo having version (0.1), but the same code failed for version (2.0) because the dynamixel servo (2.0) rotates with max.velocity (where as it's velocity should be according to the goal velocity) following the extended position limits.
Please, if someone knows what wrong I am doing! and how to modify the code... it will be great help and thanks.
Regards, Danaish Rathore