Hi barbosafs,
Unfortunately the Arduino Due, unlike the Arduino Zero doesn't have PWM oneshot built in. Although, as you code above suggests, it's possible by enabling the PWM, loading the buffered duty cycle update register (REG_PWM_CDTYUPD0), then disabling PWM to generate a single oneshot pulse on the output.
The first consideration is the timer speed. For a standard multi-rotor ESC we use 1000us to 2000us, PWM pulse widths at a frequency from 250Hz to 500Hz. For single slope PWM this is achieved using a base PWM timer frequency of 1MHz. Using this method it's possible to load the duty cycle register with the standard 1000us to 2000us values and output corresponding 1000us to 2000us pulses.
For Oneshot125 though, we require 125us to 250us pulses. To achieve these pulse widths we just need to increase the timer speed 8 times, giving us a base timer frequency of 8MHz. Using this method it's possible to load the duty cycle register with the standard 1000us to 2000us values and output corresponding 125us to 250us pulses.
The next issue is that the 84MHz clock on the Arduino Due isn't divisible by 8. However, I remembered reading an article for the Taulab's CC3D flight controller: User Guide: OneShot125 · TauLabs/TauLabs Wiki · GitHub. They instead used a 12MHz PWM timer base frequency and multiplied the standard 1000us to 2000us values by 1.5, before loading them into the duty cycle register. 12MHz works nicely for the Due as we can divide 84MHz by 7.
The oneshot is achieved as you code snippet mentioned, just by enabling PWM, loading the buffered duty cycle update register (REG_PWM_CDTYUPD0) then disabling PWM. By the way, the period is set to a value greater than 250us. This value isn't critical, as we're using oneshot rather than repeating the pulse at a given frequency. I've set the period to 2500us * 1.5 = 3750 (or 312.5us).
In the code below just load the REG_PWM_CDTYUPD0 register with the throttle value (1000us - 2000us), multiplied by 1.5. I've set it to half throttle in this example. It goes without saying, if your using a propeller, it's best to test it first with the prop off.
The following code sets up Oneshot125 output on the DAC1 pin (PWML0):
// Output Oneshot125 PWM on pin DAC1 (PWML0)
void setup()
{
// PWM Set-up on pin: DAC1
REG_PMC_PCER1 |= PMC_PCER1_PID36; // Enable PWM
REG_PIOB_ABSR |= PIO_ABSR_P16; // Set PWM pin perhipheral type A or B, in this case B
REG_PIOB_PDR |= PIO_PDR_P16; // Set PWM pin to an output
REG_PWM_CLK = PWM_CLK_PREA(0) | PWM_CLK_DIVA(7); // Set the PWM clock rate to 12MHz (84MHz/7)
REG_PWM_CMR0 = PWM_CMR_CPRE_CLKA; // Enable single slope PWM and set the clock source as CLKA
REG_PWM_CPRD0 = 3750; // Set the PWM frequency less than 4kHz to 12MHz/3750 = 3.2kHz
REG_PWM_CDTY0 = 0; // Set the PWM duty cycle to 0
REG_PWM_ENA = PWM_ENA_CHID0; // Enable the PWM channel 0
}
void loop()
{
// Delay - normally replace this line with your motor control code
delay(2); // Simulate looptime at 2ms
// Note that 1500 below is your standard ESC PWM value 1000us - min, 1500us - half and 2000us - max throttle
// Multiplied by 1.5 to account for the 12MHz timer clock, (the Due is unable to generate the 8MHz clock we require)
REG_PWM_ENA = PWM_ENA_CHID0; // Enable the PWM channel - retrigger the Oneshot125 pulse
REG_PWM_CDTYUPD0 = (unsigned long)(1500 * 1.5); // Set throttle to half throttle - WARNING this will activate the motor
REG_PWM_DIS = PWM_DIS_CHID0; // Disable the PWM channel - however the buffered pulse is still output
}