|
@ -73,9 +73,16 @@ uint16_t MarlinHAL::adc_result; |
|
|
esp_adc_cal_characteristics_t characteristics[ADC_ATTEN_MAX]; |
|
|
esp_adc_cal_characteristics_t characteristics[ADC_ATTEN_MAX]; |
|
|
adc_atten_t attenuations[ADC1_CHANNEL_MAX] = {}; |
|
|
adc_atten_t attenuations[ADC1_CHANNEL_MAX] = {}; |
|
|
uint32_t thresholds[ADC_ATTEN_MAX]; |
|
|
uint32_t thresholds[ADC_ATTEN_MAX]; |
|
|
volatile int numPWMUsed = 0, |
|
|
|
|
|
pwmPins[MAX_PWM_PINS], |
|
|
volatile int numPWMUsed = 0; |
|
|
pwmValues[MAX_PWM_PINS]; |
|
|
volatile struct { pin_t pin; int value; } pwmState[MAX_PWM_PINS]; |
|
|
|
|
|
|
|
|
|
|
|
pin_t chan_pin[CHANNEL_MAX_NUM + 1] = { 0 }; // PWM capable IOpins - not 0 or >33 on ESP32
|
|
|
|
|
|
|
|
|
|
|
|
struct { |
|
|
|
|
|
uint32_t freq; // ledcReadFreq doesn't work if a duty hasn't been set yet!
|
|
|
|
|
|
uint16_t res; |
|
|
|
|
|
} pwmInfo[(CHANNEL_MAX_NUM + 1) / 2]; |
|
|
|
|
|
|
|
|
// ------------------------
|
|
|
// ------------------------
|
|
|
// Public functions
|
|
|
// Public functions
|
|
@ -254,25 +261,81 @@ void MarlinHAL::adc_start(const pin_t pin) { |
|
|
adc1_set_attenuation(chan, atten); |
|
|
adc1_set_attenuation(chan, atten); |
|
|
} |
|
|
} |
|
|
|
|
|
|
|
|
void analogWrite(pin_t pin, int value) { |
|
|
// ------------------------
|
|
|
// Use ledc hardware for internal pins
|
|
|
// PWM
|
|
|
if (pin < 34) { |
|
|
// ------------------------
|
|
|
static int cnt_channel = 1, pin_to_channel[40] = { 0 }; |
|
|
|
|
|
if (pin_to_channel[pin] == 0) { |
|
|
int8_t channel_for_pin(const uint8_t pin) { |
|
|
ledcAttachPin(pin, cnt_channel); |
|
|
for (int i = 0; i <= CHANNEL_MAX_NUM; i++) |
|
|
ledcSetup(cnt_channel, 490, 8); |
|
|
if (chan_pin[i] == pin) return i; |
|
|
ledcWrite(cnt_channel, value); |
|
|
return -1; |
|
|
pin_to_channel[pin] = cnt_channel++; |
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// get PWM channel for pin - if none then attach a new one
|
|
|
|
|
|
// return -1 if fail or invalid pin#, channel # (0-15) if success
|
|
|
|
|
|
int8_t get_pwm_channel(const pin_t pin, const uint32_t freq, const uint16_t res) { |
|
|
|
|
|
if (!WITHIN(pin, 1, MAX_PWM_IOPIN)) return -1; // Not a hardware PWM pin!
|
|
|
|
|
|
int8_t cid = channel_for_pin(pin); |
|
|
|
|
|
if (cid >= 0) return cid; |
|
|
|
|
|
|
|
|
|
|
|
// Find an empty adjacent channel (same timer & freq/res)
|
|
|
|
|
|
for (int i = 0; i <= CHANNEL_MAX_NUM; i++) { |
|
|
|
|
|
if (chan_pin[i] == 0) { |
|
|
|
|
|
if (chan_pin[i ^ 0x1] != 0) { |
|
|
|
|
|
if (pwmInfo[i / 2].freq == freq && pwmInfo[i / 2].res == res) { |
|
|
|
|
|
chan_pin[i] = pin; // Allocate PWM to this channel
|
|
|
|
|
|
ledcAttachPin(pin, i); |
|
|
|
|
|
return i; |
|
|
|
|
|
} |
|
|
|
|
|
} |
|
|
|
|
|
else if (cid == -1) // Pair of empty channels?
|
|
|
|
|
|
cid = i & 0xFE; // Save lower channel number
|
|
|
} |
|
|
} |
|
|
ledcWrite(pin_to_channel[pin], value); |
|
|
} |
|
|
|
|
|
// not attached, is an empty timer slot avail?
|
|
|
|
|
|
if (cid >= 0) { |
|
|
|
|
|
chan_pin[cid] = pin; |
|
|
|
|
|
pwmInfo[cid / 2].freq = freq; |
|
|
|
|
|
pwmInfo[cid / 2].res = res; |
|
|
|
|
|
ledcSetup(cid, freq, res); |
|
|
|
|
|
ledcAttachPin(pin, cid); |
|
|
|
|
|
} |
|
|
|
|
|
return cid; // -1 if no channel avail
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=_BV(PWM_RESOLUTION)-1*/, const bool invert/*=false*/) { |
|
|
|
|
|
const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION); |
|
|
|
|
|
if (cid >= 0) { |
|
|
|
|
|
uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1); |
|
|
|
|
|
ledcWrite(cid, duty); |
|
|
|
|
|
} |
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
int8_t MarlinHAL::set_pwm_frequency(const pin_t pin, const uint32_t f_desired) { |
|
|
|
|
|
const int8_t cid = channel_for_pin(pin); |
|
|
|
|
|
if (cid >= 0) { |
|
|
|
|
|
if (f_desired == ledcReadFreq(cid)) return cid; // no freq change
|
|
|
|
|
|
ledcDetachPin(chan_pin[cid]); |
|
|
|
|
|
chan_pin[cid] = 0; // remove old freq channel
|
|
|
|
|
|
} |
|
|
|
|
|
return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// use hardware PWM if avail, if not then ISR
|
|
|
|
|
|
void analogWrite(const pin_t pin, const uint16_t value, const uint32_t freq/*=PWM_FREQUENCY*/, const uint16_t res/*=8*/) { // always 8 bit resolution!
|
|
|
|
|
|
// Use ledc hardware for internal pins
|
|
|
|
|
|
const int8_t cid = get_pwm_channel(pin, freq, res); |
|
|
|
|
|
if (cid >= 0) { |
|
|
|
|
|
ledcWrite(cid, value); // set duty value
|
|
|
return; |
|
|
return; |
|
|
} |
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// not a hardware PWM pin OR no PWM channels available
|
|
|
int idx = -1; |
|
|
int idx = -1; |
|
|
|
|
|
|
|
|
// Search Pin
|
|
|
// Search Pin
|
|
|
for (int i = 0; i < numPWMUsed; ++i) |
|
|
for (int i = 0; i < numPWMUsed; ++i) |
|
|
if (pwmPins[i] == pin) { idx = i; break; } |
|
|
if (pwmState[i].pin == pin) { idx = i; break; } |
|
|
|
|
|
|
|
|
// not found ?
|
|
|
// not found ?
|
|
|
if (idx < 0) { |
|
|
if (idx < 0) { |
|
@ -281,7 +344,7 @@ void analogWrite(pin_t pin, int value) { |
|
|
|
|
|
|
|
|
// Take new slot for pin
|
|
|
// Take new slot for pin
|
|
|
idx = numPWMUsed; |
|
|
idx = numPWMUsed; |
|
|
pwmPins[idx] = pin; |
|
|
pwmState[idx].pin = pin; |
|
|
// Start timer on first use
|
|
|
// Start timer on first use
|
|
|
if (idx == 0) HAL_timer_start(MF_TIMER_PWM, PWM_TIMER_FREQUENCY); |
|
|
if (idx == 0) HAL_timer_start(MF_TIMER_PWM, PWM_TIMER_FREQUENCY); |
|
|
|
|
|
|
|
@ -289,7 +352,7 @@ void analogWrite(pin_t pin, int value) { |
|
|
} |
|
|
} |
|
|
|
|
|
|
|
|
// Use 7bit internal value - add 1 to have 100% high at 255
|
|
|
// Use 7bit internal value - add 1 to have 100% high at 255
|
|
|
pwmValues[idx] = (value + 1) / 2; |
|
|
pwmState[idx].value = (value + 1) / 2; |
|
|
} |
|
|
} |
|
|
|
|
|
|
|
|
// Handle PWM timer interrupt
|
|
|
// Handle PWM timer interrupt
|
|
@ -300,9 +363,9 @@ HAL_PWM_TIMER_ISR() { |
|
|
|
|
|
|
|
|
for (int i = 0; i < numPWMUsed; ++i) { |
|
|
for (int i = 0; i < numPWMUsed; ++i) { |
|
|
if (count == 0) // Start of interval
|
|
|
if (count == 0) // Start of interval
|
|
|
WRITE(pwmPins[i], pwmValues[i] ? HIGH : LOW); |
|
|
digitalWrite(pwmState[i].pin, pwmState[i].value ? HIGH : LOW); |
|
|
else if (pwmValues[i] == count) // End of duration
|
|
|
else if (pwmState[i].value == count) // End of duration
|
|
|
WRITE(pwmPins[i], LOW); |
|
|
digitalWrite(pwmState[i].pin, LOW); |
|
|
} |
|
|
} |
|
|
|
|
|
|
|
|
// 128 for 7 Bit resolution
|
|
|
// 128 for 7 Bit resolution
|
|
|