Close

Calling the Control Loop

A project log for Portable Vertical Plotter

Small esp32 based vertical polar plotting machine.

luke-thompsonLuke Thompson 04/18/2021 at 15:450 Comments

[I wrote this project log almost a year ago and forgot to publish it. I realized that trying to do position control on a brushed dc motor was not going to work the way I would have liked, so I stopped pursuing that approach. I may come back to the problem again in the future, this time with stepper motors.]




To control the motors, we need a control loop to run at some fixed frequency that checks the current position/velocity and updates the pwm duty cycle based on what the desired position/velocity is. Ideally this loop would have accurate timing and run at higher frequencies.

Because of these requirements, we can't just place the control function in the Arduino loop, since we don't know the frequency it will run at, and since other functions might take a variable amount of time, there will be a large amount of jitter.

The second option we unfortunately have to eliminate is writing a freeRTOS task and using the 'vTaskDelayUntil' to set our timing. While this seems promising at first, this function can only delay in integer number of freeRTOS 'ticks' and will only start at the next tick. In the Arduino build of the esp-idf, this is set to one millisecond, which isn't too bad, but limits the possible frequencies to (1000 Hz, 500 Hz, 333 Hz, 250 Hz, etc.) and will have a jitter potentially bigger than one millisecond.

If we have already eliminated these 2 options, what alternatives are there? There are 3 different approaches that had potential: use a interrupt service routine (ISR), use the esp-idf high resolution timer, or use a semaphore to signal a task from an ISR.

ISR

Using an ISR sounds like the perfect solution in theory, and thus was the approach I spent the most time pursuing. The esp32 General Purpose Timer allows us to easily setup an interrupt at a fixed, configurable rate. We then can write a controller in that interrupt that will perform the calculations and update the duty cycle as needed. It is at this point that we run into the 2 (maybe 3) issues that makes this approach hard to implement. The floating point unit (FPU) is disabled in interrupts by default, and only  functions in RAM can safely be called from the interrupt.

Getting the FPU enabled wasn't too difficult thanks to this thread on the esp forum. (If we were build the esp-idf from source, we could enable this with this configuration option.)

uint32_t cp0_regs[18];    // FPU enable code from: esp32.com/viewtopic.php?t=1292#p5936
void IRAM_ATTR controlLoop() {
    // // Save and enable the FPU if needed
    // get FPU state
    uint32_t cp_state = xthal_get_cpenable();

    if(cp_state) {
        // Save FPU registers
        xthal_save_cp0(cp0_regs);
    } else {
        // enable FPU
        xthal_set_cpenable(1);
    }

    // DO WORK HERE

    if(cp_state) {
        // Restore FPU registers
        xthal_restore_cp0(cp0_regs);
    } else {
        // turn it back off
        xthal_set_cpenable(0);
    }
}

The other issue is a bit more insidious. If the cpu is in the process of reading from the flash (such as when the web server serves a webpage from SPIFFS) when the ISR is triggered, then the ISR is unable to read anything from memory, including functions. If this situation happens, the esp32 core panics with a message such as: "Guru Meditation Error: Core 1 panic'ed (Cache disabled but cached memory region accessed"

The simplest way to address this is to add the "IRAM_ATTR"  attribute to any functions called by the ISR. This works ok if the only functions that we are calling are ones we wrote (though we do give up some RAM in the process), but breaks down if we need to call library functions such as the 'pcnt_get_counter_value' and 'mcpwm_set_duty'.

In order to access the hardware peripherals, we need to access them directly. To figure out how to do that, I read through the source for the esp-idf drivers (ex pcnt) and tried to follow function calls until I found where the values were being directly written to (ex pcnt). I was able to figure that out for the pulse counter, but I wasn't able to figure out how to access the MCPWM peripheral. I found some things that I thought would work, but wasn't able to get it to compile.

// Read pulse counter register
count = (int16_t) PCNT.cnt_unit[pcntUnit].cnt_val;

// Attempt to set duty cycle (couldn't get to compile)
MCPWM0[mcpwm_num]->channel[timer_num].cmpr_value[op_num].cmpr_val = set_duty;

It was at this point, I started to think that maybe this wasn't the right approach. I was hacking my way through a lot of limitations, and maybe there was a better way to do it. That is when I came across this post which suggests 2 ways to potentially achieve what we need.

High Resolution Timer

The esp-idf high resolution timers provides yet another way to run code at periodic intervals (see example here). It has a very simple and clean interface but in my brief experiments with it, I saw high amounts of jitter (greater than 1 ms). I believe that is caused by the task waiting for the next freeRTOS tick to start.

    const esp_timer_create_args_t periodic_timer_args = {
        .callback = &periodic_timer_callback,
    };

    esp_timer_handle_t periodic_timer;
    ESP_ERROR_CHECK(esp_timer_create(&periodic_timer_args, &periodic_timer));

    /* Start the timers */
    // ESP_ERROR_CHECK(esp_timer_start_periodic(periodic_timer, 1000));

static void periodic_timer_callback(void* arg)
{
    // Do stuff here
}

 The benefit of this approach over the ISR approach is its ease of use. Besides the timing issue, everything works as you would expect. No need to manually safe FPU registers, the esp32 doesn't crash when reading from SPIFFS (though the control loop can be delayed), and there isn't a need to store all functions in RAM. The large amount of jitter is problematic though, which is why I tried the 3rd approach to see if it would be any better.

Semaphores

The 3rd approach is somewhat a combination of the previous 2. It uses an ISR for timing, but runs all of the actual code in a freeRTOS task that is high priority. The key to getting low jitter is to have the ISR yield directly to the task so that it starts running immediately and doesn't need to wait for the next freeRTOS tick. I based the code heavily off of the example given in this post and used the ISR timer I had already set up. Below is the important parts of how this method works, though I highly recommend reading [ESP_Angus]'s post since they do a good job explaining how and why the code is the way it is.

static SemaphoreHandle_t timer_sem;

// In setup:
 xTaskCreatePinnedToCore(sample_timer_task, "sample_timer", 4096, NULL, configMAX_PRIORITIES - 1, NULL, 1);


void IRAM_ATTR onTimer(){
   static BaseType_t xHigherPriorityTaskWoken = pdFALSE;
   xSemaphoreGiveFromISR(timer_sem, &xHigherPriorityTaskWoken);
   if( xHigherPriorityTaskWoken) {
       portYIELD_FROM_ISR(); // this wakes up sample_timer_task immediately
}


void sample_timer_task(void *param)
{
    timer_sem = xSemaphoreCreateBinary();

    // timer group init and config goes here (timer_group example gives code for doing this)
    initTimer();

    // timer_isr_register(timer_group, timer_idx, timer_isr_handler, NULL, ESP_INTR_FLAG_IRAM, NULL);

    while (1) {
        xSemaphoreTake(timer_sem, portMAX_DELAY);
        // Do work here
    }
}

With this method, I achieved very low jitter (usually less than 20 microseconds) and the system doesn't crash when reading from SPIFFS (though again, this interrupts the loop and it can take multiple milliseconds until it runs again). Currently this seems to be the best option and I haven't run into any issues yet.

Discussions