energia / Energia

Fork of Arduino for the Texas Instruments LaunchPad's
http://energia.nu
Other
794 stars 672 forks source link

analogWrite fails at consecutive calls with delay <100ms #203

Closed gompf closed 11 years ago

gompf commented 11 years ago

I am using Energia 0101E0009 for Windows with a Stellaris Launchpad LM4F120H5QR. Goals is to use hardware pwm for multicopter esc control. With a loop delay of more than 100ms analogWrite looks OK on the oszi, but when called faster it shows kind of "one shot" behavior. Pulstime is OK but frequency becomes unstable. Tested on Timers and WTimers, behavior is the same. I asume this is due to to reload of TimerLoadSet/re-enabling the timer with every analogWrite through PWMWrite. As the frequency is ment to be fixed at 490Hz to stay close to Arduino it should be possible to move the TimerLoadSet/enabling to init and just change the MatchSet/PrescalerMatchSet during analogWrite.

g2mis3 commented 11 years ago

i also try this......how to generate the 50hz pwm.

gompf commented 11 years ago

Sorry for late response, was busy... If you look into wiring_analog.c you see that analogWrite is a "two staged call":

void analogWrite(uint8_t pin, int val) { // // duty cycle(%) = val / 255; // Frequency of 490Hz specified by Arduino API // PWMWrite(pin, 255, val, 490); }

Here you can change the 490 to the frequency you want.

To get a stable baseline during fast calls I modified PWMWrite,

/_if (duty == 0) { pinMode(pin, OUTPUT); digitalWrite(pin, LOW); } else if (duty >= analogres) { pinMode(pin, OUTPUT); digitalWrite(pin, HIGH); }/

added a cutdown PWMWrite/call function

void PWMWriteFast(uint8_t pin, uint32_t analog_res, uint32_t duty, unsigned int freq) { uint8_t bit = digitalPinToBitMask(pin); // get pin bit uint8_t port = digitalPinToPort(pin); // get pin port uint8_t timer = digitalPinToTimer(pin); uint32_t portBase = (uint32_t) portBASERegister(port); uint32_t offset = timerToOffset(timer); uint32_t timerBase = getTimerBase(offset); uint32_t timerAB = TIMER_A << timerToAB(timer);

    if (port == NOT_A_PORT) return;     // pin on timer?
    uint32_t periodPWM = ROM_SysCtlClockGet()/freq;
    //just set compare register values
    ROM_TimerMatchSet(timerBase, timerAB, (analog_res-duty)*periodPWM/analog_res);
    //
    // If using a 16-bit timer, with a periodPWM > 0xFFFF,
    // need to use a prescaler
    //
    if((offset < WTIMER0) && (periodPWM > 0xFFFF)) {
        ROM_TimerPrescaleMatchSet(timerBase, timerAB,
            (((analog_res-duty)*periodPWM/analog_res) & 0xFFFF0000) >> 16);
    }

}

void analogWriteFast(uint8_t pin, int val) { // // duty cycle(%) = val / 255; // Frequency of 490Hz specified by Arduino API // PWMWriteFast(pin, 255, val, 490); } . . .

and made it public in Energia.H . . . void analogWrite(uint8_t, int); void analogWriteFast(uint8_t, int); void analogReference(uint16_t); . . .

By this analogWrite can be used to initialise the timers and analogWriteFast for fast calls/only match set changes after init.