Added "invert" option to LedPin()
If invert=true, PWM output will be phase-inverted. This is useful when creating a pair of PWM pins that need to be out of phase by 180 degrees (e.g driving a piezo-electric buzzer via two PWM pins).
This commit is contained in:
parent
a8271c8724
commit
6d18d5a3dc
|
|
@ -29,7 +29,7 @@
|
||||||
|
|
||||||
///////////////////
|
///////////////////
|
||||||
|
|
||||||
LedC::LedC(uint8_t pin, uint16_t freq){
|
LedC::LedC(uint8_t pin, uint16_t freq, boolean invert){
|
||||||
|
|
||||||
if(freq==0)
|
if(freq==0)
|
||||||
freq=DEFAULT_PWM_FREQ;
|
freq=DEFAULT_PWM_FREQ;
|
||||||
|
|
@ -44,10 +44,7 @@ LedC::LedC(uint8_t pin, uint16_t freq){
|
||||||
timerList[nTimer][nMode]->speed_mode=(ledc_mode_t)nMode;
|
timerList[nTimer][nMode]->speed_mode=(ledc_mode_t)nMode;
|
||||||
timerList[nTimer][nMode]->timer_num=(ledc_timer_t)nTimer;
|
timerList[nTimer][nMode]->timer_num=(ledc_timer_t)nTimer;
|
||||||
timerList[nTimer][nMode]->freq_hz=freq;
|
timerList[nTimer][nMode]->freq_hz=freq;
|
||||||
|
|
||||||
#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 0, 0)
|
|
||||||
timerList[nTimer][nMode]->clk_cfg=LEDC_USE_APB_CLK;
|
timerList[nTimer][nMode]->clk_cfg=LEDC_USE_APB_CLK;
|
||||||
#endif
|
|
||||||
|
|
||||||
int res=LEDC_TIMER_BIT_MAX-1; // find the maximum possible resolution
|
int res=LEDC_TIMER_BIT_MAX-1; // find the maximum possible resolution
|
||||||
while(getApbFrequency()/(freq*pow(2,res))<1)
|
while(getApbFrequency()/(freq*pow(2,res))<1)
|
||||||
|
|
@ -68,9 +65,7 @@ LedC::LedC(uint8_t pin, uint16_t freq){
|
||||||
channelList[nChannel][nMode]->channel=(ledc_channel_t)nChannel;
|
channelList[nChannel][nMode]->channel=(ledc_channel_t)nChannel;
|
||||||
channelList[nChannel][nMode]->timer_sel=(ledc_timer_t)nTimer;
|
channelList[nChannel][nMode]->timer_sel=(ledc_timer_t)nTimer;
|
||||||
channelList[nChannel][nMode]->intr_type=LEDC_INTR_DISABLE;
|
channelList[nChannel][nMode]->intr_type=LEDC_INTR_DISABLE;
|
||||||
#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 4, 0)
|
channelList[nChannel][nMode]->flags.output_invert=invert;
|
||||||
channelList[nChannel][nMode]->flags.output_invert=0;
|
|
||||||
#endif
|
|
||||||
channelList[nChannel][nMode]->hpoint=0;
|
channelList[nChannel][nMode]->hpoint=0;
|
||||||
channelList[nChannel][nMode]->gpio_num=pin;
|
channelList[nChannel][nMode]->gpio_num=pin;
|
||||||
timer=timerList[nTimer][nMode];
|
timer=timerList[nTimer][nMode];
|
||||||
|
|
@ -85,18 +80,19 @@ LedC::LedC(uint8_t pin, uint16_t freq){
|
||||||
|
|
||||||
///////////////////
|
///////////////////
|
||||||
|
|
||||||
LedPin::LedPin(uint8_t pin, float level, uint16_t freq) : LedC(pin, freq){
|
LedPin::LedPin(uint8_t pin, float level, uint16_t freq, boolean invert) : LedC(pin, freq, invert){
|
||||||
|
|
||||||
if(!channel)
|
if(!channel)
|
||||||
Serial.printf("\n*** ERROR: Can't create LedPin(%d) - no open PWM channels and/or Timers ***\n\n",pin);
|
Serial.printf("\n*** ERROR: Can't create LedPin(%d) - no open PWM channels and/or Timers ***\n\n",pin);
|
||||||
else
|
else
|
||||||
Serial.printf("LedPin=%d: mode=%d channel=%d, timer=%d, freq=%d Hz, resolution=%d bits\n",
|
Serial.printf("LedPin=%d: mode=%d channel=%d, timer=%d, freq=%d Hz, resolution=%d bits %s\n",
|
||||||
channel->gpio_num,
|
channel->gpio_num,
|
||||||
channel->speed_mode,
|
channel->speed_mode,
|
||||||
channel->channel,
|
channel->channel,
|
||||||
channel->timer_sel,
|
channel->timer_sel,
|
||||||
timer->freq_hz,
|
timer->freq_hz,
|
||||||
timer->duty_resolution
|
timer->duty_resolution,
|
||||||
|
channel->flags.output_invert?"(inverted)":""
|
||||||
);
|
);
|
||||||
|
|
||||||
set(level);
|
set(level);
|
||||||
|
|
|
||||||
|
|
@ -59,7 +59,7 @@ class LedC {
|
||||||
ledc_channel_config_t *channel=NULL;
|
ledc_channel_config_t *channel=NULL;
|
||||||
ledc_timer_config_t *timer;
|
ledc_timer_config_t *timer;
|
||||||
|
|
||||||
LedC(uint8_t pin, uint16_t freq);
|
LedC(uint8_t pin, uint16_t freq, boolean invert=false);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
int getPin(){return(channel?channel->gpio_num:-1);} // returns the pin number
|
int getPin(){return(channel?channel->gpio_num:-1);} // returns the pin number
|
||||||
|
|
@ -75,8 +75,8 @@ class LedC {
|
||||||
class LedPin : public LedC {
|
class LedPin : public LedC {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
LedPin(uint8_t pin, float level=0, uint16_t freq=DEFAULT_PWM_FREQ); // assigns pin to be output of one of 16 PWM channels initial level and frequency
|
LedPin(uint8_t pin, float level=0, uint16_t freq=DEFAULT_PWM_FREQ, boolean invert=false); // assigns pin to be output of one of 16 PWM channels initial level and frequency
|
||||||
void set(float level); // sets the PWM duty to level (0-100)
|
void set(float level); // sets the PWM duty to level (0-100)
|
||||||
|
|
||||||
static void HSVtoRGB(float h, float s, float v, float *r, float *g, float *b ); // converts Hue/Saturation/Brightness to R/G/B
|
static void HSVtoRGB(float h, float s, float v, float *r, float *g, float *b ); // converts Hue/Saturation/Brightness to R/G/B
|
||||||
};
|
};
|
||||||
|
|
|
||||||
|
|
@ -45,9 +45,7 @@ RFControl::RFControl(uint8_t pin, boolean refClock, boolean installDriver){
|
||||||
config->rmt_mode=RMT_MODE_TX;
|
config->rmt_mode=RMT_MODE_TX;
|
||||||
config->tx_config.carrier_en=false;
|
config->tx_config.carrier_en=false;
|
||||||
config->channel=(rmt_channel_t)nChannels;
|
config->channel=(rmt_channel_t)nChannels;
|
||||||
#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 4, 0)
|
|
||||||
config->flags=0;
|
config->flags=0;
|
||||||
#endif
|
|
||||||
config->clk_div = 1;
|
config->clk_div = 1;
|
||||||
config->mem_block_num=1;
|
config->mem_block_num=1;
|
||||||
config->gpio_num=(gpio_num_t)pin;
|
config->gpio_num=(gpio_num_t)pin;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue