Koduino
|
PWM output:
PWM
PWM input can be accomplished using two underlying methods: using a timer input channel (pin needs to be connected to a general purpose timer channel), or using an external interrupt (can only have one per PinSource—this is the last digit in 0–15 of the pin name).
PWM_IN
, call pinRemap() to change the timer connected to a pinPWM_IN
or PWM_IN_EXTI
Functions | |
void | analogWriteResolution (uint8_t nbits) |
Set the resolution for the analogWrite() function. More... | |
void | analogWriteFrequency (uint8_t pin, int freqHz) |
Assign a PWM frequency to the specified pin (default = 1000 Hz) More... | |
void | analogWriteFloat (uint8_t pin, float duty) |
Change the PWM duty cycle on a pin. More... | |
void | analogWrite (uint8_t pin, uint32_t duty) |
Change the PWM duty cycle on a pin. More... | |
float | pwmIn (uint8_t pin) |
Read a PWM signal (non-blocking) More... | |
void | pwmInExpectedPeriod (int expectedUs) |
Set the expected period for PWM_IN or PWM_IN_EXTI. More... | |
void analogWrite | ( | uint8_t | pin, |
uint32_t | duty | ||
) |
Change the PWM duty cycle on a pin.
This should have the same effect as the Arduino function, but it is not efficient on systems without a floating point (as implemented), since it calls analogWriteFloat() under the hood.
pin | |
duty | The new duty cycle in [0,2^n] where n is the bit resolution set by analogWriteResolution() (default 8) |
void analogWriteFloat | ( | uint8_t | pin, |
float | duty | ||
) |
Change the PWM duty cycle on a pin.
Unlike Arduino, pinMode() must have been called on the pin beforehand with PWM
. Also, the duty cycle is specified in floating point, and the resolution is only limited by the timer (see analogWriteFrequency()).
pin | |
duty | The new duty cycle in normalized floating point from 0.0 (0%) to 1.0 (100%). |
void analogWriteFrequency | ( | uint8_t | pin, |
int | freqHz | ||
) |
Assign a PWM frequency to the specified pin (default = 1000 Hz)
Please see the pin remapping documentation for more details about connected timers to pins, including defaults. This function will change the PWM frequency for all pins connected to the same timer.
Gory details:
pin | Pin to change frequency on |
freqHz | New frequency in Hz (default is 1000) |
void analogWriteResolution | ( | uint8_t | nbits | ) |
Set the resolution for the analogWrite() function.
Note that this has no effect on the actual PWM resolution, which is determined by the period of the PWM (see analogWriteFrequency()). This also has no effect on analogWriteFloat()
nbits | Number of bits used in analogWrite() (default is 8, as in Arduino) |
float pwmIn | ( | uint8_t | pin | ) |
Read a PWM signal (non-blocking)
pinMode() with PWM_IN
must have been called on the pin before-hand. Unlike Arduino, this function does not block and wait. It uses high-speed timer interrupts to catch rising and falling edges, and keeps track of the time when these happen to estimate the PWM duty cycle.
Advanced:
~~~ TIMER_MAP[ PIN_MAP[ pin ].timer ].channelData[ PIN_MAP[ pin ].channel-1].period
~~~ will return the PWM period in units such that 36000 -> 1ms, 3600 -> 0.1ms etc.
pin | Pin to read |
void pwmInExpectedPeriod | ( | int | expectedUs | ) |
Set the expected period for PWM_IN or PWM_IN_EXTI.
expectedUs | Expected period in microseconds (default 1000) |