ROBOTIS-GIT / Dynamixel2Arduino

DYNAMIXEL protocol library for Arduino
Apache License 2.0
88 stars 55 forks source link

Dynamixel2Arduino::begin() hangs if called after creating FreeRTOS tasks #115

Open johnauld opened 1 year ago

johnauld commented 1 year ago

The problem is actually in SerialPortHandler::begin(), which calls delay(). This redirects to HAL_Delay(), which ultimately relies on the STM32 HAL's timer tick ISR running. However, calling into the FreeRTOS API apparently disables interrupts until the scheduler is started. Per [https://www.freertos.org/FAQHelp.html]():

If a FreeRTOS API function is called before the scheduler has been started then interrupts will deliberately be left disabled, and not re-enable again until the first task starts to execute.

HAL_Delay() spins until the tick count reaches the necessary value, but since the tick ISR is not running, the tick count never increments, and therefore HAL_Delay() never returns.

The following code demonstrates the problem:

#include <RTOS.h>
#include <Dynamixel2Arduino.h>

void setup() {
    Serial.begin(57600);
    while ( !Serial ) delay(10);

    Serial.print("Creating task 1: ");
    auto res = xTaskCreate([](void*) { while (true); }, "task1", 512, nullptr, 3, nullptr );
    Serial.println( (res == pdPASS) ? "succeeded" : "failed" );

    Dynamixel2Arduino   dxl {Serial3};
    dxl.begin(57600);                           // <---------------- ** hangs here **

    Serial.print("Creating task 2: ");
    res = xTaskCreate([](void*) { while (true); }, "task2", 512, nullptr, 3, nullptr );
    Serial.println( (res == pdPASS) ? "succeeded" : "failed" );

    Serial.println("Starting scheduler");
    vTaskStartScheduler();
    Serial.println("Failed to start scheduler");
}

void loop() {}  // No-op under FreeRTOS

The comment ** hangs here ** shows the location of the problem. Dynamixel2Arduino::begin() calls SerialPortHandler::begin(). I added some instrumentation to the latter function to trace execution by turning on board LEDs:

void SerialPortHandler::begin(unsigned long baud)
{
digitalWrite(BDPIN_LED_USER_1, LOW);                                    // <---- This line executes
#if defined(ARDUINO_OpenCM904)
  if(port_ == Serial1 && getOpenState() == false){
    Serial1.setDxlMode(true);
  }
#elif defined(ARDUINO_OpenRB)
  if(port_ == Serial1 && getOpenState() == false){
    pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
    digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
    delay(300); // Wait for the FET to turn on.
  }
#elif defined(ARDUINO_OpenCR)
  if(port_ == Serial3 && getOpenState() == false){
    pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
    digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
  }
digitalWrite(BDPIN_LED_USER_2, LOW);                                    // <---- This line executes
  delay(300); // Wait for the DYNAMIXEL to power up normally.
digitalWrite(BDPIN_LED_USER_3, LOW);                                    // <---- This line is never reached
#endif
digitalWrite(BDPIN_LED_USER_4, LOW);

  baud_ = baud;
  port_.begin(baud_);
  mbedTXdelayus = 24000000 / baud;

  if(dir_pin_ != -1){
    pinMode(dir_pin_, OUTPUT);
    digitalWrite(dir_pin_, LOW);
    while(digitalRead(dir_pin_) != LOW);
  }

  setOpenState(true);
}