Firmware Update for XC330 using Dynamixel Shield for Arduino MKR?

DYNAMIXEL Actuator

XC330-T181-T (V46 firmware)

Issue Description

I am trying to update the firmware on my XC330 motors (from V46 to V50) using Dynamixel Wizard 2.0.

I have an Arduino MKR Zero with Dynamixel Shield for Arduino MKR and was wondering if it is possible to perform a firmware update using this controller, or if I need to use a different setup (e.g. U2D2 + SMPS2Dynamixel).

I found several examples for USB passthrough to make Arduino + Dynamixel Wizard 2.0 work together, e.g.:

OpenCR github repo (usb_to_dxl.ino)

OpenRB-150 github repo (usb_to_dynamixel.ino)

Dynamixel2Arduino github repo (partial implementation: add_custom_SerialPortHandler.ino)

I ‘wrote’ a minimum working example based on the three code samples above:

#include <DynamixelShield.h>

#define COMPUTER_USB Serial
#define DXL_PACKET_BUFFER_LENGTH  1024

uint8_t packet_buffer[DXL_PACKET_BUFFER_LENGTH];
unsigned long led_update_time = 0;

DynamixelShield dxl;

void setup() {
  // put your setup code here, to run once:
  // set USB connection for communication with Dynamixel Wizard 2.0
  COMPUTER_USB.begin(57600);

  // set DXL direction pin to baseline
  digitalWrite(DXL_DIR_PIN, LOW);
  while(digitalRead(DXL_DIR_PIN) != LOW);
  
  // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
  dxl.begin(57600);
}

void loop() {
  // put your main code here, to run repeatedly:
  dataTransceiver();
}

void dataTransceiver()
{
  int length = 0;
  int i = 0;

  // USB -> DXL (set dxl direction pin high during TX to dxl)
  length = COMPUTER_USB.available();
  if( length > 0 )
  {
    digitalWrite(DXL_DIR_PIN, HIGH);
    while(digitalRead(DXL_DIR_PIN) != HIGH);
    for(i = 0; i < length; i++)
    {
      DXL_SERIAL.write(COMPUTER_USB.read());
    }
    DXL_SERIAL.flush();
    digitalWrite(DXL_DIR_PIN, LOW);
    while(digitalRead(DXL_DIR_PIN) != LOW);
  }

  // DXL -> USB
  length = DXL_SERIAL.available();
  if( length > 0 )
  {
    if( length > DXL_PACKET_BUFFER_LENGTH )
    {
      length = DXL_PACKET_BUFFER_LENGTH;
    }
    for(i = 0; i < length; i++)
    {
      packet_buffer[i] = DXL_SERIAL.read();
    }
    COMPUTER_USB.write(packet_buffer, length);
  }
}

This works fine to receive data from the XC330 and modify the control table (screenshot example):

Unfortunately, the firmware update gets stuck at the following screen:

I tried the ‘Recovery’ option but it gets stuck here (to ‘turn off power’ I am just unplugging the 12V SMPS, and then plugging it in a few seconds later, because the DynamixelShield for MKR doesn’t have a power switch):
stuck_recovery_mode

Any advice is appreciated! If there is a reason this won’t be possible, I can just buy the separate U2D2 + SMPS2Dynamixel, but it seems so close to actually working. At least, I hope this can help anyone trying to get the Dynamixel Wizard 2.0 working with DynamixelShield.

One thing I noticed is that the code example from OpenCR has:

    drv_dxl_tx_enable(TRUE);
    for(i=0; i<length; i++ )
    {
      DXL_PORT.write(CMD_PORT.read());
      DXL_PORT.flush();
    }
    drv_dxl_tx_enable(FALSE);

While my example has:

    digitalWrite(DXL_DIR_PIN, HIGH);
    while(digitalRead(DXL_DIR_PIN) != HIGH);
    for(i = 0; i < length; i++)
    {
      DXL_SERIAL.write(COMPUTER_USB.read());
    }
    DXL_SERIAL.flush();
    digitalWrite(DXL_DIR_PIN, LOW);
    while(digitalRead(DXL_DIR_PIN) != LOW);

Because putting DXL_SERIAL.flush() inside the for loop made most writes to DXL fail (for example, ping and reboot worked, but writing to control table or turning torque on did not).

So maybe I am missing something else with the buffering/serial reading/flushing to allow for the (larger?) firmware communication to occur. Or, the implementation is too slow reading one byte at a time and the buffer fills up? Or, there is some other limitation related to firmware updates I’m unaware of.

Thank you for reading!

1 Like

When you get the step requesting a reset of the DYNAMIXEL, can you try unplugging and replugging the DYNAMIXEL itself into the MKR Shield? It’s possible the reset of the full arduino board is causing that hang that you are seeing during the firmware reset.

As for the flush inside/outside the loop, it makes more sense to me to keep it outside as you do in your example, since it doesn’t make sense to me to flush serial console a bunch of times during a send, but I’ll admit that I’m not super familiar with the intricacies of sending raw serial data like this. If trying the different reboot strategy doesn’t work I can reach out to some experts who might have more insight into this process.

1 Like

@Jonathon @efun

I can confirm that efun’s code works on my MKR ZERO and XL-330-M288, and it can do Firmware Recovery also if I used the power on/off technique described by jonathon. However, it also looks like that it can only do Firmware Recovery at 57.6 Kbps.

Thank you for sharing!

Huh, I was planning on trying an XL330-288T I had lying around, just in case it had something to do with the XC330.

Before I did that, I tried again with the XC330 and it just… updated firmware immediately without an issue when I clicked the “Update” button :exploding_head:

I did find that my XC330 motors have high idle temperature as noted by another user. When I started them up and did firmware update, they were at 45C, a few minutes later they’re at 57C. If there’s any chance the temperature would affect the firmware update… :sweat_smile:

Anyway, I’ll mark this as solved, and glad I could get the firmware update working with my setup!

As a follow-up, I also got Dynamixel Wizard 2.0 (somewhat) working with Portenta H7.

From my code sample in my original post, I added at the top:

// [...]
const uint32_t GLOBAL_BAUDRATE = 57600;
unsigned int mbedTXdelayus = round(24000000 / GLOBAL_BAUDRATE); // added this line
// [...]

Because the serial handler for Mbed Arduinos like Portenta H7 required some modifications (see the github issue here, for example).

And after the serial flush, adding the delay:

    // [...]
    DXL_SERIAL.flush();
    #if defined(ARDUINO_ARCH_MBED)        // these
      delayMicroseconds(mbedTXdelayus);   // lines
    #endif                                // added
    digitalWrite(DXL_DIR_PIN, LOW);
    // [...]

After these fixes, the scan/ping in Dynamixel Wizard 2.0 still didn’t work. However, when I did a manual ping from Python (using ping.py taken from Dynamixel SDK python):

… suddenly I was able to Scan/Ping from Dynamixel Wizard 2.0!!

I’m really not sure why the manual ping is required. I went back and removed the Mbed-specific parts of code and I couldn’t even manually ping from Python, so the delayMicroseconds(mbedTXdelayus) is definitely required. It isn’t the "succeeded to change the baudrate" part, because I can remove that from ping.py and it works fine.

One weird thing with Dynamixel Wizard is that when I start from a fresh connection (unplug->plug USB cable), I cannot ‘Send’ a packet:

On the MKR Zero example, I could always click Send and it would list the packet at the top (first line), but not receive any response (when usb_to_dynamixel.ino wasn’t working - no second line).

After ping from Python, I get both lines:

So something wonky is going on, would be curious if anyone can figure it out! But it’s functional for now :sweat_smile:

1 Like

So far I cannot use methods scan or ping with the Current Dynamixel2Arduino library with any controller OpenRB-150, MKR Zero or Portenta H7 also. But the other methods such as goal position and goal velocity work fine. So I just don’t use scan or ping in my work.