🍻 STM32 set_pwm_duty "on/off" for digital pins (#23665)

This commit is contained in:
Mike La Spina 2022-02-04 13:33:52 -06:00 committed by Scott Lahteine
parent d4801461f5
commit a07d7e4b8a
3 changed files with 39 additions and 31 deletions

View file

@ -30,7 +30,8 @@
static uint16_t timer_freq[TIMER_NUM];
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
const uint16_t duty = invert ? v_size - v : v;
if (PWM_PIN(pin)) {
const PinName pin_name = digitalPinToPinName(pin);
TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
@ -50,11 +51,15 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255
// Note the resolution is sticky here, the input can be upto 16 bits and that would require RESOLUTION_16B_COMPARE_FORMAT (16)
// If such a need were to manifest then we would need to calc the resolution based on the v_size parameter and add code for it.
const uint16_t value = invert ? v_size - v : v;
HT->setCaptureCompare(channel, value, RESOLUTION_8B_COMPARE_FORMAT); // Sets the duty, the calc is done in the library :)
HT->setCaptureCompare(channel, duty, RESOLUTION_8B_COMPARE_FORMAT); // Set the duty, the calc is done in the library :)
pinmap_pinout(pin_name, PinMap_PWM); // Make sure the pin output state is set.
if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
}
else {
pinMode(pin, OUTPUT);
digitalWrite(pin, duty < v_size / 2 ? LOW : HIGH);
}
}
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer

View file

@ -39,17 +39,20 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) {
}
void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
if (!PWM_PIN(pin)) return;
const uint16_t duty = invert ? v_size - v : v;
if (PWM_PIN(pin)) {
timer_dev *timer; UNUSED(timer);
if (timer_freq[timer_and_index_for_pin(pin, &timer)] == 0)
set_pwm_frequency(pin, PWM_FREQUENCY);
const uint8_t channel = PIN_MAP[pin].timer_channel;
const uint16_t duty = invert ? v_size - v : v;
timer_set_compare(timer, channel, duty);
timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
}
else {
pinMode(pin, OUTPUT);
digitalWrite(pin, duty < v_size / 2 ? LOW : HIGH);
}
}
void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer

View file

@ -150,10 +150,10 @@
// Timer Definitions
// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin
#ifndef TIMER_TONE
#define TIMER_TONE TIM6
#define TIMER_TONE TIM6 // TIMER_TONE must be defined in this file
#endif
#ifndef TIMER_SERVO
#define TIMER_SERVO TIM7
#define TIMER_SERVO TIM7 // TIMER_SERVO must be defined in this file
#endif
// UART Definitions