DYNAMIXEL MX28(1.0) and MX106(2.0) with OpenCM9.04 and OpenCM 485 EXP + Push button control

Hi everyone. I am controlling two DYNAMIXEL MX28(1.0) and MX106(2.0) with OpenCM9.04. And Dynamixel2Arduino library is used for uploading the code. And power source is SMPS (12V, 5A) connected to 485 EXP board.

Sketch code includes Current-based Position control mode for MX106 protocol 2, and Extended Position control mode for MX28 protocol 1 and simple push button code to operate the DYNAMIXEL.

Here the sketch code is working fine however, sometimes either of the one or both DYNAMIXEL instantaneous stops for few Milliseconds and then run normally following the button commands. This some time happened after few rotations of MX or also by pressing the push buttons randomly.

The sample code is attached here

// DYNAMIXEL IDs and Protocol
const uint8_t DXL_ID = 1;
const uint8_t DXL_ID3 = 2;
const float DXL_PROTOCOL_VERSION = 2.0;
const float DXL_PROTOCOL_VERSION1 = 1.0;

void setup() {
// Use Serial to debug.
  DEBUG_SERIAL.begin(115200);
  
  // initialize the pushbutton pin as an input:
  pinMode(buttonPin1, INPUT);
  pinMode(buttonPin2, INPUT);
  pinMode(buttonPin3, INPUT);
  pinMode(buttonPin4, INPUT);

  
  dxl.begin(57600);                                        // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
  dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);        // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
  dxl.ping(DXL_ID);                                        // Get DYNAMIXEL information
  dxl.writeControlTableItem(TORQUE_ENABLE, DXL_ID, 0);     // Turn off torque
  dxl.setOperatingMode(DXL_ID, OP_CURRENT_BASED_POSITION); // Operating Mode
  dxl.writeControlTableItem(CURRENT_LIMIT, DXL_ID, 500);   // for Mx(2.0)
  dxl.writeControlTableItem(TORQUE_ENABLE, DXL_ID, 1);     // Turn on torque
  dxl.writeControlTableItem(GOAL_CURRENT, DXL_ID, Torque_ID);    // Goal Torque for Mx(2.0)
  dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, Velocity_ID); // for Mx(2.0)

   dxl3.begin(57600);
   dxl3.setPortProtocolVersion(DXL_PROTOCOL_VERSION1);
   dxl3.ping(DXL_ID3);
   dxl3.writeControlTableItem(TORQUE_ENABLE, DXL_ID3, 0);
   dxl3.setOperatingMode(DXL_ID3, OP_EXTENDED_POSITION);
   dxl3.writeControlTableItem(MAX_TORQUE, DXL_ID3, 500);   // for Mx(1.0)
   dxl3.writeControlTableItem(TORQUE_ENABLE, DXL_ID3, 1);
   dxl3.writeControlTableItem(TORQUE_LIMIT, DXL_ID3, Torque_ID3); // for Mx(1.0)
   dxl3.writeControlTableItem(MOVING_SPEED, DXL_ID3, Velocity_ID3);  // for Mx-28T(1.0)
}

void loop() {
  // read the state of the pushbutton value:
  buttonState1 = digitalRead(buttonPin1);
  buttonState2 = digitalRead(buttonPin2);
  buttonState3 = digitalRead(buttonPin3);
  buttonState4 = digitalRead(buttonPin4);

 //Get present position of DXL
   a=dxl.getPresentPosition(DXL_ID);
   a2=dxl3.getPresentPosition(DXL_ID3);

if (buttonState1 == 0 && buttonState2 == 1) {           // First button
  a=a+100;
  dxl.setGoalPosition(DXL_ID, a);} 
else if (buttonState1 == 1 && buttonState2 == 0) {        // Second button
  a=a-100;
  dxl.setGoalPosition(DXL_ID, a); }

if (buttonState3 == 0 && buttonState4 == 1) {           // First button
  a2=a2+50;
  dxl3.setGoalPosition(DXL_ID3, a2);}
else if (buttonState3 == 1 && buttonState4 == 0) {           // Second button
  a2=a2-50;
  dxl3.setGoalPosition(DXL_ID3, a2);}
}

The hardware Figure can be seen here


I am really not sure where the actual problem is… as the code seems fine and moreover it is working. The problem is only that sometimes DYNAMIXEL stops for just Milliseconds and I couldn’t figure out why this is happening. Any suggestions would be appreciated.

Thanks a lot.

@RATHORE
Can you show how you defined objects dxl and dxl3?

Thank you for your reply. I just edited the same code of dxl with dxl3 (or it can be dxl1 or dxl2) for protocol (1.0) or vice versa and it worked. I know for the same version DYNAMIXEL no need of changing dxl. You can correct me here if the above code requires any modifications.

The reason I asked about the definitions of dxl and dxl3 is that my approach for mixed protocols (when using “Dynamixel2Arduino” library) had been to use only 1 dxl object pointing to only 1 physical serial port (Serial3 in this case), and then to change/switch the protocol (1.0 or 2.0) just before sending some kind of command to a specific DXL. Please see this post.

image

With your approach, it seemed that you associated “statically” 2 DXL objects (with different protocols) to the same physical Serial3 port (?), I am just guessing as you did not provide a direct answer to my previous comment. With your approach, the convenience is that you did not have to flip-flop “protocols” like in my approach. But I do not know for sure which way the ROBOTIS programmers want us to use their library. So let me also try your approach on my system for AX-12A and 2XL430 (using RC-100 Buttons) to see if there is any difference between the 2 approaches, then we both can learn possibly something new :grinning:.

Thank you again for sharing your approach. Actually I hadn’t any good answer for your previous question therefore I just simply described that how I did it. After trying please update here if it works.

In your own code, when you used dxl.begin(57600) and dxl3.begin(57600), you must have previously defined these two Dynamixel2Arduino objects dxl and dxl3 in the Global Variables section above the void setup() section. For example, in my code, I used the objects dxl_1 and dxl_3 and the picture below shows how I defined them:

Can you share how you defined your Dynamixel2Arduino objects dxl and dxl3? This is what I need to determine first. Thanks.

I have used the same serial for both protocols. Maybe this could be the main reason that the either of the DXL sometimes was stopping (for a few Milliseconds) and moving again.

  #define DXL_SERIAL   Serial3    //OpenCM9.04 EXP Board's DXL port Serial
  #define DEBUG_SERIAL Serial
  const uint8_t DXL_DIR_PIN = 22; //OpenCM9.04 EXP Board's DIR PIN
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
Dynamixel2Arduino dxl3(DXL_SERIAL, DXL_DIR_PIN);
1 Like

Hmmmm…

Is there any reason to use MX-28 with Protocol 1.0?

Not really sure what cause of instaneous stop the malfunction is caused by the mixed protocol or your hardwawre (button idle state issue such as Pull-up Pull-Down) itself. But let’s figugure out one by one

  1. MX-28 (Protocol 1.0)'s Maximum Position Velue at Extended Position Mode is 28,672 in CCW, ~7 turns (Can be extended by dividing resolution). If you are writing value over 28,672. Probabably unexpected issue can be observed. So you should reset the position around the maximum. (Highly recommended usung MX-28(2.0) protocol)

  2. Increase the Baudrate(Addr 4 or 8) upto 115200 or 1M bps and decrease Return Delay Time(Addr 5 or 9)

See what’s happening.

I just checked using both approaches on my system (1 AX-12A and 1 2XL-430 on 485-EXP board), and both approaches worked fine for me. So, it looks like that it is OK to have multiple Dynamixel2Arduino objects created with different DXL protocols but pointing to the same physical COM Port. It is also OK to use only 1 Dynamixel2Arduino object per COM Port, and then switch “protocol” in and out as needed for different DXLs having different protocols but connected via the same COM Port.

The real issue then may be among the ones that Yogurt_Man suggested in his post. You probably already found that Arduino has a sketch named “Debounce” under “Built-in Examples >> Digital >> Debounce” that can be useful.

1 Like

Thank you again for your suggestions. Actually, I was just testing MX(1.0) with other dynamixel protocol (2.0) to make sure that whether the dynamixel2arduino library works or not in this case.

I think the instantaneous stop should be not because of the limited rotation of MX28(1.0) (~7 turns) as the MX106(2.0) is also behaving similarly. it must be because of using mixed protocols.

Furthermore, I also tried the same hardware with 4 dynamixels (2 MX106 and 2 MX28) all having protocol (1.0) and everything was ok.

I haven’t tried it I hope may be it should work.

Thank you again for updating your testing work. here I am not very sure that the approach which I used, will work well. As I have tested many times; the servos run smoothly using mixed protocols but at the same time I am also getting the issue like instantaneous stopping/running of MX servo (both protocols).