mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-30 09:39:49 +02:00
PWM fix and simplification (#722)
* PWM fix and simplification This is an alternative solution to the PWM/ISR/float problem. 1. The set_level() argument is the exact value that is passed to the LEDC Write function. It can be interpreted as the numerator of a rational fraction whose denominator is the max PWM value, i.e. the precision, == 1 << _resolution_bits 2. There is a new denominator() method that returns the precision. 3. The sys_pwm_control(mask, duty, synchronize) function is replaced by two functions sys_analog_all_off() and sys_set_analog(io_num, duty). This closely matches the actual usage. The old routine was called from two places, one where the mask was alway 0xFF, the duty was always 0, and synchronize was always false. That is the one that was troublesome from ISR context. The other call always affected a single pin, so the mask formulation with its loop was useless extra baggage. By splitting into two functions, each one becomes much simpler, thus faster and easier to understand. The "synchronize" argument and associated logic moved out to the caller (GCode.cpp), which more closely reflects the behavioral logic. 4. For symmetry, sys_io_control() was similarly split. 5. sys_calc_pwm_precision() was moved into UserOutput.cpp since is it driver specific, not a general system routine. * Update Grbl.h * Delete template.h Co-authored-by: bdring <barton.dring@gmail.com>
This commit is contained in:
@@ -1401,10 +1401,11 @@ Error gc_execute_line(char* line, uint8_t client) {
|
|||||||
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync) ||
|
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync) ||
|
||||||
(gc_block.modal.io_control == IoControl::DigitalOnImmediate) || (gc_block.modal.io_control == IoControl::DigitalOffImmediate)) {
|
(gc_block.modal.io_control == IoControl::DigitalOnImmediate) || (gc_block.modal.io_control == IoControl::DigitalOffImmediate)) {
|
||||||
if (gc_block.values.p < MaxUserDigitalPin) {
|
if (gc_block.values.p < MaxUserDigitalPin) {
|
||||||
if (!sys_io_control(
|
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync)) {
|
||||||
bit((int)gc_block.values.p),
|
protocol_buffer_synchronize();
|
||||||
(gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOnImmediate),
|
}
|
||||||
(gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync))) {
|
bool turnOn = gc_block.modal.io_control == IoControl::DigitalOnSync || gc_block.modal.io_control == IoControl::DigitalOnImmediate;
|
||||||
|
if (!sys_set_digital((int)gc_block.values.p, turnOn)) {
|
||||||
FAIL(Error::PParamMaxExceeded);
|
FAIL(Error::PParamMaxExceeded);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
@@ -1414,8 +1415,12 @@ Error gc_execute_line(char* line, uint8_t client) {
|
|||||||
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
|
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
|
||||||
if (gc_block.values.e < MaxUserDigitalPin) {
|
if (gc_block.values.e < MaxUserDigitalPin) {
|
||||||
gc_block.values.q = constrain(gc_block.values.q, 0.0, 100.0); // force into valid range
|
gc_block.values.q = constrain(gc_block.values.q, 0.0, 100.0); // force into valid range
|
||||||
if (!sys_pwm_control(bit((int)gc_block.values.e), gc_block.values.q, (gc_block.modal.io_control == IoControl::SetAnalogSync)))
|
if (gc_block.modal.io_control == IoControl::SetAnalogSync) {
|
||||||
|
protocol_buffer_synchronize();
|
||||||
|
}
|
||||||
|
if (!sys_set_analog((int)gc_block.values.e, gc_block.values.q)) {
|
||||||
FAIL(Error::PParamMaxExceeded);
|
FAIL(Error::PParamMaxExceeded);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
FAIL(Error::PParamMaxExceeded);
|
FAIL(Error::PParamMaxExceeded);
|
||||||
}
|
}
|
||||||
|
@@ -23,7 +23,7 @@
|
|||||||
// Grbl versioning system
|
// Grbl versioning system
|
||||||
|
|
||||||
const char* const GRBL_VERSION = "1.3a";
|
const char* const GRBL_VERSION = "1.3a";
|
||||||
const char* const GRBL_VERSION_BUILD = "20201230";
|
const char* const GRBL_VERSION_BUILD = "20210101";
|
||||||
|
|
||||||
//#include <sdkconfig.h>
|
//#include <sdkconfig.h>
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
@@ -505,8 +505,8 @@ void mc_reset() {
|
|||||||
coolant_stop();
|
coolant_stop();
|
||||||
|
|
||||||
// turn off all User I/O immediately
|
// turn off all User I/O immediately
|
||||||
sys_io_control(0xFF, LOW, false);
|
sys_digital_all_off();
|
||||||
sys_pwm_control(0xFF, 0, false);
|
sys_analog_all_off();
|
||||||
#ifdef ENABLE_SD_CARD
|
#ifdef ENABLE_SD_CARD
|
||||||
// do we need to stop a running SD job?
|
// do we need to stop a running SD job?
|
||||||
if (get_sd_state(false) == SDState::BusyPrinting) {
|
if (get_sd_state(false) == SDState::BusyPrinting) {
|
||||||
|
@@ -267,36 +267,29 @@ void system_exec_control_pin(ControlPins pins) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
|
void sys_digital_all_off() {
|
||||||
// It uses a mask so all can be turned of in ms_reset
|
|
||||||
bool sys_io_control(uint8_t io_num_mask, bool turnOn, bool synchronized) {
|
|
||||||
bool cmd_ok = true;
|
|
||||||
if (synchronized)
|
|
||||||
protocol_buffer_synchronize();
|
|
||||||
|
|
||||||
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
||||||
if (io_num_mask & bit(io_num)) {
|
myDigitalOutputs[io_num]->set_level(LOW);
|
||||||
if (!myDigitalOutputs[io_num]->set_level(turnOn))
|
|
||||||
cmd_ok = false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
return cmd_ok;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
|
// io_num is the virtual digital pin#
|
||||||
// It uses a mask so all can be turned of in ms_reset
|
bool sys_set_digital(uint8_t io_num, bool turnOn) {
|
||||||
bool sys_pwm_control(uint8_t io_num_mask, float duty, bool synchronized) {
|
return myDigitalOutputs[io_num]->set_level(turnOn);
|
||||||
bool cmd_ok = true;
|
}
|
||||||
if (synchronized)
|
|
||||||
protocol_buffer_synchronize();
|
|
||||||
|
|
||||||
|
// Turn off all analog outputs
|
||||||
|
void sys_analog_all_off() {
|
||||||
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
||||||
if (io_num_mask & bit(io_num)) {
|
myAnalogOutputs[io_num]->set_level(0);
|
||||||
if (!myAnalogOutputs[io_num]->set_level(duty))
|
|
||||||
cmd_ok = false;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
return cmd_ok;
|
}
|
||||||
|
|
||||||
|
// io_num is the virtual analog pin#
|
||||||
|
bool sys_set_analog(uint8_t io_num, float percent) {
|
||||||
|
auto analog = myAnalogOutputs[io_num];
|
||||||
|
uint32_t numerator = percent / 100.0 * analog->denominator();
|
||||||
|
return analog->set_level(numerator);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@@ -170,8 +170,9 @@ void system_convert_array_steps_to_mpos(float* position, int32_t* steps);
|
|||||||
void controlCheckTask(void* pvParameters);
|
void controlCheckTask(void* pvParameters);
|
||||||
void system_exec_control_pin(ControlPins pins);
|
void system_exec_control_pin(ControlPins pins);
|
||||||
|
|
||||||
bool sys_io_control(uint8_t io_num_mask, bool turnOn, bool synchronized);
|
bool sys_set_digital(uint8_t io_num, bool turnOn);
|
||||||
bool sys_pwm_control(uint8_t io_num_mask, float duty, bool synchronized);
|
void sys_digital_all_off();
|
||||||
|
bool sys_set_analog(uint8_t io_num, float percent);
|
||||||
|
void sys_analog_all_off();
|
||||||
|
|
||||||
int8_t sys_get_next_PWM_chan_num();
|
int8_t sys_get_next_PWM_chan_num();
|
||||||
uint8_t sys_calc_pwm_precision(uint32_t freq);
|
|
||||||
|
@@ -64,8 +64,17 @@ namespace UserOutput {
|
|||||||
if (pin == UNDEFINED_PIN)
|
if (pin == UNDEFINED_PIN)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
// determine the highest bit precision allowed by frequency
|
// determine the highest resolution (number of precision bits) allowed by frequency
|
||||||
_resolution_bits = sys_calc_pwm_precision(_pwm_frequency);
|
|
||||||
|
uint32_t apb_frequency = getApbFrequency();
|
||||||
|
|
||||||
|
// increase the precision (bits) until it exceeds allow by frequency the max or is 16
|
||||||
|
_resolution_bits = 0;
|
||||||
|
while ((1 << _resolution_bits) < (apb_frequency / _pwm_frequency) && _resolution_bits <= 16) {
|
||||||
|
++_resolution_bits;
|
||||||
|
}
|
||||||
|
// _resolution_bits is now just barely too high, so drop it down one
|
||||||
|
--_resolution_bits;
|
||||||
|
|
||||||
init();
|
init();
|
||||||
}
|
}
|
||||||
@@ -89,9 +98,7 @@ namespace UserOutput {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// returns true if able to set value
|
// returns true if able to set value
|
||||||
bool AnalogOutput::set_level(float percent) {
|
bool AnalogOutput::set_level(uint32_t numerator) {
|
||||||
float duty;
|
|
||||||
|
|
||||||
// look for errors, but ignore if turning off to prevent mask turn off from generating errors
|
// look for errors, but ignore if turning off to prevent mask turn off from generating errors
|
||||||
if (_pin == UNDEFINED_PIN) {
|
if (_pin == UNDEFINED_PIN) {
|
||||||
return false;
|
return false;
|
||||||
@@ -102,15 +109,14 @@ namespace UserOutput {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_current_value == percent)
|
if (_current_value == numerator) {
|
||||||
return true;
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
_current_value = percent;
|
_current_value = numerator;
|
||||||
|
|
||||||
duty = (percent / 100.0) * (1 << _resolution_bits);
|
ledcWrite(_pwm_channel, numerator);
|
||||||
|
|
||||||
ledcWrite(_pwm_channel, duty);
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@@ -41,17 +41,18 @@ namespace UserOutput {
|
|||||||
public:
|
public:
|
||||||
AnalogOutput();
|
AnalogOutput();
|
||||||
AnalogOutput(uint8_t number, uint8_t pin, float pwm_frequency);
|
AnalogOutput(uint8_t number, uint8_t pin, float pwm_frequency);
|
||||||
bool set_level(float percent);
|
bool set_level(uint32_t numerator);
|
||||||
|
uint32_t denominator() { return 1UL << _resolution_bits; };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void init();
|
void init();
|
||||||
void config_message();
|
void config_message();
|
||||||
|
|
||||||
uint8_t _number = UNDEFINED_PIN;
|
uint8_t _number = UNDEFINED_PIN;
|
||||||
uint8_t _pin = UNDEFINED_PIN;
|
uint8_t _pin = UNDEFINED_PIN;
|
||||||
uint8_t _pwm_channel = -1; // -1 means invalid or not setup
|
uint8_t _pwm_channel = -1; // -1 means invalid or not setup
|
||||||
float _pwm_frequency;
|
float _pwm_frequency;
|
||||||
uint8_t _resolution_bits;
|
uint8_t _resolution_bits;
|
||||||
float _current_value;
|
uint32_t _current_value;
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
Reference in New Issue
Block a user