Arduino Nano 33 BLE high-frequency PWM for more than 4 pins

Arduino Nano 33 BLE analogWrite PWM possible only for 4 pins out of the box:

void loop() {
analogWrite(2, 2);
analogWrite(3, 3);
analogWrite(4, 4);
analogWrite(5, 5);
//analogWrite(10, 6);
//analogWrite(11, 7);
//analogWrite(12, 9);
}

Any combination that contains more than 4 PWM crashes my board. It starts blinking 4 short, 4 long and attempts to upload a new program fails. Only double-click on the reset button and upload a new program helps. Looks like it supports only 4 PWM outputs at one time.

SOLUTION found: https://forum.arduino.cc/index.php?topic=677826.msg4564144#msg4564144

ArduinoNano33Ble.png

Split from an old topic

Is this problem specific to the nano 33 ble - have you tried your program on a regular Uno or nano?

What is connected to the analogWrite() pins?

...R

The Nano 33 BLE has hardware support for 4√ó4 PWM channels. There are 4 PWM modules, with 4 channels each. A single module has a single counter, and 4 comparator channels with a waveform generator that can be connected to any pin.

The Arduino Core for the Nano 33 BLE uses Mbed OS:

If you dig through the Mbed OS source code for the specific target, you'll find that eventually, it'll call the nordic_pwm_init function:

    /* Default configuration:
     * 1 pin per instance, otherwise they would share base count.
     * 1 MHz clock source to match the 1 us resolution.
     */
    nrfx_pwm_config_t config = {
        .output_pins  = {
            obj->pin,
            NRFX_PWM_PIN_NOT_USED,
            NRFX_PWM_PIN_NOT_USED,
            NRFX_PWM_PIN_NOT_USED,
        },
        .irq_priority = PWM_DEFAULT_CONFIG_IRQ_PRIORITY,
        .base_clock   = NRF_PWM_CLK_1MHz,
        .count_mode   = NRF_PWM_MODE_UP,
        .top_value    = obj->period,
        .load_mode    = NRF_PWM_LOAD_COMMON,
        .step_mode    = NRF_PWM_STEP_AUTO,
    };

As you can see, it uses a single PWM module for each pin, and it keeps the three other pins unused.
This means that when you initialize a fifth PWM pin, the assertion that checks if there are any PWM modules available fails, resulting in the blinking LED:

In other words, with the default Arduino and Mbed OS functions, you can only use 4 PWM pins. If you want to use all 16 PWM channels, you can do this by using the Nordic PWM functions directly:

Pieter

Robin2:
Is this problem specific to the nano 33 ble - have you tried your program on a regular Uno or nano?

What is connected to the analogWrite() pins?

...R

Thank you for this quick response, Robin2.

I don't have any other boards. It is my very first Arduino board. By the way, I love it! :slight_smile: BLE + IMU + many PWMs = perfect for my task (I am doing balancing robot using 2 gimbal BLDC motors).

PieterP:
The Nano 33 BLE has hardware support for 4√ó4 PWM channels. There are 4 PWM modules, with 4 channels each. A single module has a single counter, and 4 comparator channels with a waveform generator that can be connected to any pin.
https://content.arduino.cc/assets/Nano_BLE_MCU-nRF52840_PS_v1.1.pdf

The Arduino Core for the Nano 33 BLE uses Mbed OS:
ArduinoCore-nRF528x-mbedos/wiring_analog.cpp at 548a18edadffa39292177026612d96990488844f · arduino/ArduinoCore-nRF528x-mbedos · GitHub

If you dig through the Mbed OS source code for the specific target, you'll find that eventually, it'll call the nordic_pwm_init function:
mbed-os/pwmout_api.c at 33e392e9d979b9e6f7fa9b9ebcd1ba10b9852b8f · ARMmbed/mbed-os · GitHub

    /* Default configuration:

* 1 pin per instance, otherwise they would share base count.
    * 1 MHz clock source to match the 1 us resolution.
    */
    nrfx_pwm_config_t config = {
        .output_pins  = {
            obj->pin,
            NRFX_PWM_PIN_NOT_USED,
            NRFX_PWM_PIN_NOT_USED,
            NRFX_PWM_PIN_NOT_USED,
        },
        .irq_priority = PWM_DEFAULT_CONFIG_IRQ_PRIORITY,
        .base_clock  = NRF_PWM_CLK_1MHz,
        .count_mode  = NRF_PWM_MODE_UP,
        .top_value    = obj->period,
        .load_mode    = NRF_PWM_LOAD_COMMON,
        .step_mode    = NRF_PWM_STEP_AUTO,
    };



As you can see, it uses a single PWM module for each pin, and it keeps the three other pins unused.
This means that when you initialize a fifth PWM pin, the assertion that checks if there are any PWM modules available fails, resulting in the blinking LED:
https://github.com/ARMmbed/mbed-os/blob/33e392e9d979b9e6f7fa9b9ebcd1ba10b9852b8f/targets/TARGET_NORDIC/TARGET_NRF5x/TARGET_NRF52/pwmout_api.c#L146

In other words, with the default Arduino and Mbed OS functions, you can only use 4 PWM pins. If you want to use all 16 PWM channels, you can do this by using the Nordic PWM functions directly:
https://github.com/NordicSemiconductor/nrfx/blob/master/drivers/include/nrfx_pwm.h
https://github.com/arduino/ArduinoCore-nRF528x-mbedos/blob/beac74ca3cd9d07363f66cf9cda6b143e4385cd2/cores/arduino/mbed/targets/TARGET_NORDIC/TARGET_NRF5x/TARGET_SDK_11/drivers_nrf/hal/nrf_pwm.h

Pieter

PieterP, that was super informative! Right now I am trying to use nrfx_pwm.h according to your suggestion. It's hard to do without any Arduino based examples. I found lots of GitHub examples ("nrfx_pwm_config_t nrfx_pwm_init NRFX_PWM_INSTANCE nrfx_pwm_simple_playback NRF_PWM_LOAD_INDIVIDUAL"). Slowly playing around... It's my first C project ever :slight_smile:

Here is my working prototype.

It controls 2 brushless motors, using 6 high-frequency PWM outputs (3,4,5 and 10, 11, 12) of my Arduino Nano 33 BLE. And they work silently :slight_smile:

Perfect, and thank you PieterP!

#include "nrfx_pwm.h"

static nrfx_pwm_t pwm1 = NRFX_PWM_INSTANCE(0);
static nrfx_pwm_t pwm2 = NRFX_PWM_INSTANCE(1);

static nrf_pwm_values_individual_t seq1_values[] = {0, 0, 0, 0};
static nrf_pwm_values_individual_t seq2_values[] = {0, 0, 0, 0};

const int VOLTAGE_DIVIDER = 4;

static nrf_pwm_sequence_t seq1 = {
    .values = {
        .p_individual = seq1_values
    },
    .length          = NRF_PWM_VALUES_LENGTH(seq1_values),
    .repeats         = 1,
    .end_delay       = 0
};

static nrf_pwm_sequence_t seq2 = {
    .values = {
        .p_individual = seq2_values
    },
    .length          = NRF_PWM_VALUES_LENGTH(seq2_values),
    .repeats         = 1,
    .end_delay       = 0
};

const int pwmSin[] = {128, 132, 136, 140, 143, 147, 151, 155, 159, 162, 166, 170, 174, 178, 181, 185, 189, 192, 196, 200, 203, 207, 211, 214, 218, 221, 225, 228, 232, 235, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 248, 249, 250, 250, 251, 252, 252, 253, 253, 253, 254, 254, 254, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 254, 254, 254, 253, 253, 253, 252, 252, 251, 250, 250, 249, 248, 248, 247, 246, 245, 244, 243, 242, 241, 240, 239, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 248, 249, 250, 250, 251, 252, 252, 253, 253, 253, 254, 254, 254, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 254, 254, 254, 253, 253, 253, 252, 252, 251, 250, 250, 249, 248, 248, 247, 246, 245, 244, 243, 242, 241, 240, 239, 238, 235, 232, 228, 225, 221, 218, 214, 211, 207, 203, 200, 196, 192, 189, 185, 181, 178, 174, 170, 166, 162, 159, 155, 151, 147, 143, 140, 136, 132, 128, 124, 120, 116, 113, 109, 105, 101, 97, 94, 90, 86, 82, 78, 75, 71, 67, 64, 60, 56, 53, 49, 45, 42, 38, 35, 31, 28, 24, 21, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 8, 7, 6, 6, 5, 4, 4, 3, 3, 3, 2, 2, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 3, 3, 3, 4, 4, 5, 6, 6, 7, 8, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 8, 7, 6, 6, 5, 4, 4, 3, 3, 3, 2, 2, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 3, 3, 3, 4, 4, 5, 6, 6, 7, 8, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 21, 24, 28, 31, 35, 38, 42, 45, 49, 53, 56, 60, 64, 67, 71, 75, 78, 82, 86, 90, 94, 97, 101, 105, 109, 113, 116, 120, 124};

int currentStepA;
int currentStepB;
int currentStepC;
int sineArraySize;
int increment = 1;

void setup() {

    nrfx_pwm_config_t config1 = {
        .output_pins  = {
            32+ 12, // Arduino pin 3
            32+ 15, // Arduino pin 4
            32+ 13, // Arduino pin 5
            NRFX_PWM_PIN_NOT_USED,
        },
        .irq_priority = 7,
        .base_clock   = NRF_PWM_CLK_4MHz,
        .count_mode   = NRF_PWM_MODE_UP,
        .top_value    = 256,
        .load_mode    = NRF_PWM_LOAD_INDIVIDUAL,
        .step_mode    = NRF_PWM_STEP_AUTO,
    };

    nrfx_pwm_init(&pwm1, &config1, NULL);

    nrfx_pwm_config_t config2 = {
        .output_pins  = {
            32 + 2, // Arduino pin 10
            32 + 1, // Arduinopin 11
            32 + 8, // Arduino pin 12
            NRFX_PWM_PIN_NOT_USED,
        },
        .irq_priority = 7,
        .base_clock   = NRF_PWM_CLK_4MHz,
        .count_mode   = NRF_PWM_MODE_UP,
        .top_value    = 256,
        .load_mode    = NRF_PWM_LOAD_INDIVIDUAL,
        .step_mode    = NRF_PWM_STEP_AUTO,
    };

    nrfx_pwm_init(&pwm2, &config2, NULL);

    pinMode(2, OUTPUT);
    pinMode(9, OUTPUT);
    digitalWrite(2, HIGH);
    digitalWrite(9, HIGH);

    sineArraySize = sizeof(pwmSin)/sizeof(int); // Find lookup table size
  int phaseShift = sineArraySize / 3;         // Find phase shift and initial A, B C phase values
  currentStepA = 0;
  currentStepB = currentStepA + phaseShift;
  currentStepC = currentStepB + phaseShift;

  sineArraySize--;
}

void loop() {
    
  currentStepA = currentStepA + increment;
  currentStepB = currentStepB + increment;
  currentStepC = currentStepC + increment;

  //Check for lookup table overflow and return to opposite end if necessary
  if(currentStepA > sineArraySize)  currentStepA = 0;
  if(currentStepA < 0)  currentStepA = sineArraySize;
 
  if(currentStepB > sineArraySize)  currentStepB = 0;
  if(currentStepB < 0)  currentStepB = sineArraySize;
 
  if(currentStepC > sineArraySize)  currentStepC = 0;
  if(currentStepC < 0) currentStepC = sineArraySize;
  setMotor1(pwmSin[currentStepA], pwmSin[currentStepB], pwmSin[currentStepC]);
  setMotor2(pwmSin[currentStepA], pwmSin[currentStepB], pwmSin[currentStepC]);
  delay(10);
}

void setMotor1(int a, int b, int c) {
    (*seq1_values).channel_0 = (255 - a) / VOLTAGE_DIVIDER;
    (*seq1_values).channel_1 = (255 - b) / VOLTAGE_DIVIDER;
    (*seq1_values).channel_2 = (255 - c) / VOLTAGE_DIVIDER;
    (void)nrfx_pwm_simple_playback(&pwm1, &seq1, 1, NRFX_PWM_FLAG_LOOP);
}

void setMotor2(int a, int b, int c) {
    (*seq2_values).channel_0 = (255 - a) / VOLTAGE_DIVIDER;
    (*seq2_values).channel_1 = (255 - b) / VOLTAGE_DIVIDER;
    (*seq2_values).channel_2 = (255 - c) / VOLTAGE_DIVIDER;
    (void)nrfx_pwm_simple_playback(&pwm2, &seq2, 1, NRFX_PWM_FLAG_LOOP);
}

Inspired by BerryJam ‚Äď Spining BLDC(Gimbal) motors at super slooooooow speeds with Arduino and L6234

1 Like