mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 11:22:38 +02:00
LEDC honors :low on output pin
This commit is contained in:
@@ -31,6 +31,7 @@
|
|||||||
#include "RcServo.h"
|
#include "RcServo.h"
|
||||||
|
|
||||||
#include "../Machine/MachineConfig.h"
|
#include "../Machine/MachineConfig.h"
|
||||||
|
#include "../Pins/Ledc.h"
|
||||||
#include "../Pin.h"
|
#include "../Pin.h"
|
||||||
#include "../Report.h"
|
#include "../Report.h"
|
||||||
#include "../Limits.h" // limitsMaxPosition
|
#include "../Limits.h" // limitsMaxPosition
|
||||||
@@ -45,12 +46,9 @@ namespace Motors {
|
|||||||
void RcServo::init() {
|
void RcServo::init() {
|
||||||
_axis_index = axis_index();
|
_axis_index = axis_index();
|
||||||
|
|
||||||
auto pwmNative = _pwm_pin.getNative(Pin::Capabilities::PWM);
|
|
||||||
|
|
||||||
read_settings();
|
read_settings();
|
||||||
_channel_num = sys_get_next_PWM_chan_num();
|
_channel_num = sys_get_next_PWM_chan_num();
|
||||||
ledcSetup(_channel_num, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
|
ledcInit(_pwm_pin, _channel_num, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
|
||||||
ledcAttachPin(pwmNative, _channel_num);
|
|
||||||
_current_pwm_duty = 0;
|
_current_pwm_duty = 0;
|
||||||
|
|
||||||
_disabled = true;
|
_disabled = true;
|
||||||
@@ -74,7 +72,7 @@ namespace Motors {
|
|||||||
}
|
}
|
||||||
|
|
||||||
_current_pwm_duty = duty;
|
_current_pwm_duty = duty;
|
||||||
ledcWrite(_channel_num, duty);
|
ledcSetDuty(_channel_num, duty);
|
||||||
}
|
}
|
||||||
|
|
||||||
// sets the PWM to zero. This allows most servos to be manually moved
|
// sets the PWM to zero. This allows most servos to be manually moved
|
||||||
|
@@ -18,6 +18,7 @@
|
|||||||
|
|
||||||
#include "PwmPin.h"
|
#include "PwmPin.h"
|
||||||
|
|
||||||
|
#include "../Pins/Ledc.h"
|
||||||
#include "../Pin.h"
|
#include "../Pin.h"
|
||||||
#include "../Assert.h"
|
#include "../Assert.h"
|
||||||
#include "LimitedResource.h"
|
#include "LimitedResource.h"
|
||||||
@@ -107,9 +108,8 @@ namespace PinUsers {
|
|||||||
|
|
||||||
resolutionBits_ = calculatePwmPrecision(frequency);
|
resolutionBits_ = calculatePwmPrecision(frequency);
|
||||||
|
|
||||||
ledcSetup(pwmChannel_, frequency, resolutionBits_);
|
ledcInit(pin, pwmChannel_, frequency, resolutionBits_);
|
||||||
ledcAttachPin(native, pwmChannel_);
|
ledcSetDuty(pwmChannel_, 0);
|
||||||
ledcWrite(pwmChannel_, 0);
|
|
||||||
|
|
||||||
// info_serial("PWM Output:%d on Pin:%s Freq:%0.0fHz", _number, _pin.name().c_str(), _pwm_frequency);
|
// info_serial("PWM Output:%d on Pin:%s Freq:%0.0fHz", _number, _pin.name().c_str(), _pwm_frequency);
|
||||||
|
|
||||||
@@ -129,13 +129,13 @@ namespace PinUsers {
|
|||||||
}
|
}
|
||||||
|
|
||||||
auto duty = value * (uint32_t(1) << int(resolutionBits_));
|
auto duty = value * (uint32_t(1) << int(resolutionBits_));
|
||||||
ledcWrite(pwmChannel_, uint32_t(duty));
|
ledcSetDuty(pwmChannel_, uint32_t(duty));
|
||||||
}
|
}
|
||||||
|
|
||||||
~NativePwm() override {
|
~NativePwm() override {
|
||||||
auto native = pin_.getNative(Pin::Capabilities::PWM | Pin::Capabilities::Native);
|
auto native = pin_.getNative(Pin::Capabilities::PWM | Pin::Capabilities::Native);
|
||||||
|
|
||||||
ledcWrite(pwmChannel_, 0);
|
ledcSetDuty(pwmChannel_, 0);
|
||||||
ledcDetachPin(native);
|
ledcDetachPin(native);
|
||||||
|
|
||||||
// Release resource:
|
// Release resource:
|
||||||
|
@@ -26,6 +26,7 @@
|
|||||||
*/
|
*/
|
||||||
#include "10vSpindle.h"
|
#include "10vSpindle.h"
|
||||||
|
|
||||||
|
#include "../Pins/Ledc.h"
|
||||||
#include "../Report.h"
|
#include "../Report.h"
|
||||||
#include "../System.h" // sys.spindle_speed
|
#include "../System.h" // sys.spindle_speed
|
||||||
|
|
||||||
@@ -39,10 +40,7 @@ namespace Spindles {
|
|||||||
return; // We cannot continue without the output pin
|
return; // We cannot continue without the output pin
|
||||||
}
|
}
|
||||||
|
|
||||||
auto outputPin = _output_pin.getNative(Pin::Capabilities::PWM);
|
ledcInit(_output_pin, _pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||||
|
|
||||||
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
|
||||||
ledcAttachPin(outputPin, _pwm_chan_num); // attach the PWM to the pin
|
|
||||||
|
|
||||||
_enable_pin.setAttr(Pin::Attr::Output);
|
_enable_pin.setAttr(Pin::Attr::Output);
|
||||||
_direction_pin.setAttr(Pin::Attr::Output);
|
_direction_pin.setAttr(Pin::Attr::Output);
|
||||||
|
@@ -32,6 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#include "BESCSpindle.h"
|
#include "BESCSpindle.h"
|
||||||
|
|
||||||
|
#include "../Pins/Ledc.h"
|
||||||
#include "../Report.h"
|
#include "../Report.h"
|
||||||
|
|
||||||
#include <soc/ledc_struct.h>
|
#include <soc/ledc_struct.h>
|
||||||
@@ -51,9 +52,7 @@ namespace Spindles {
|
|||||||
_pwm_precision = 16;
|
_pwm_precision = 16;
|
||||||
_pwm_period = (1 << _pwm_precision);
|
_pwm_period = (1 << _pwm_precision);
|
||||||
|
|
||||||
auto outputNative = _output_pin.getNative(Pin::Capabilities::PWM);
|
ledcInit(_output_pin, _pwm_chan_num, double(_pwm_freq), _pwm_precision); // setup the channel
|
||||||
ledcSetup(_pwm_chan_num, double(_pwm_freq), _pwm_precision); // setup the channel
|
|
||||||
ledcAttachPin(outputNative, _pwm_chan_num); // attach the PWM to the pin
|
|
||||||
|
|
||||||
_enable_pin.setAttr(Pin::Attr::Output);
|
_enable_pin.setAttr(Pin::Attr::Output);
|
||||||
|
|
||||||
@@ -84,7 +83,7 @@ namespace Spindles {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// to prevent excessive calls to ledcWrite, make sure duty has changed
|
// to prevent excessive calls to ledcSetDuty, make sure duty has changed
|
||||||
if (duty == _current_pwm_duty) {
|
if (duty == _current_pwm_duty) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@@ -97,15 +96,7 @@ namespace Spindles {
|
|||||||
// full on value is a 2ms pulse.
|
// full on value is a 2ms pulse.
|
||||||
uint32_t pulse_counts = _min_pulse_counts + ((duty * _pulse_span_counts) >> _pwm_precision);
|
uint32_t pulse_counts = _min_pulse_counts + ((duty * _pulse_span_counts) >> _pwm_precision);
|
||||||
|
|
||||||
// This was ledcWrite, but this is called from an ISR
|
ledcSetDuty(_pwm_chan_num, pulse_counts);
|
||||||
// and ledcWrite uses RTOS features not compatible with ISRs
|
|
||||||
LEDC.channel_group[0].channel[0].duty.duty = pulse_counts << 4;
|
|
||||||
|
|
||||||
// bool on = !!duty;
|
|
||||||
bool on = true; // Never turn off the pulse train
|
|
||||||
|
|
||||||
LEDC.channel_group[0].channel[0].conf0.sig_out_en = on;
|
|
||||||
LEDC.channel_group[0].channel[0].conf1.duty_start = on;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// prints the startup message of the spindle config
|
// prints the startup message of the spindle config
|
||||||
|
@@ -21,14 +21,10 @@
|
|||||||
*/
|
*/
|
||||||
#include "PWMSpindle.h"
|
#include "PWMSpindle.h"
|
||||||
|
|
||||||
#include <soc/ledc_struct.h>
|
|
||||||
#include <driver/ledc.h>
|
|
||||||
|
|
||||||
#include "../System.h" // sys.report_ovr_counter
|
#include "../System.h" // sys.report_ovr_counter
|
||||||
#include "../GCode.h" // gc_state.modal
|
#include "../GCode.h" // gc_state.modal
|
||||||
#include "../Logging.h"
|
#include "../Logging.h"
|
||||||
|
#include "../Pins/Ledc.h"
|
||||||
extern "C" void __pinMode(uint8_t pin, uint8_t mode);
|
|
||||||
|
|
||||||
// ======================= PWM ==============================
|
// ======================= PWM ==============================
|
||||||
/*
|
/*
|
||||||
@@ -63,15 +59,7 @@ namespace Spindles {
|
|||||||
|
|
||||||
auto outputNative = _output_pin.getNative(Pin::Capabilities::PWM);
|
auto outputNative = _output_pin.getNative(Pin::Capabilities::PWM);
|
||||||
|
|
||||||
ledcSetup(_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
ledcInit(_output_pin, _pwm_chan_num, (double)_pwm_freq, _pwm_precision);
|
||||||
|
|
||||||
// This is equivalent to ledcAttachPin with the addition of
|
|
||||||
// using the hardware inversion function in the GPIO matrix.
|
|
||||||
// We use that to apply the active low function in hardware.
|
|
||||||
__pinMode(outputNative, OUTPUT);
|
|
||||||
uint8_t function = ((_pwm_chan_num / 8) ? LEDC_LS_SIG_OUT0_IDX : LEDC_HS_SIG_OUT0_IDX) + (_pwm_chan_num % 8);
|
|
||||||
bool isActiveLow = _output_pin.getAttr().has(Pin::Attr::ActiveLow);
|
|
||||||
pinMatrixOutAttach(outputNative, function, isActiveLow, false);
|
|
||||||
|
|
||||||
_enable_pin.setAttr(Pin::Attr::Output);
|
_enable_pin.setAttr(Pin::Attr::Output);
|
||||||
_direction_pin.setAttr(Pin::Attr::Output);
|
_direction_pin.setAttr(Pin::Attr::Output);
|
||||||
@@ -142,25 +130,14 @@ namespace Spindles {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// to prevent excessive calls to ledcWrite, make sure duty has changed
|
// to prevent excessive calls to ledcSetDuty, make sure duty has changed
|
||||||
if (duty == _current_pwm_duty) {
|
if (duty == _current_pwm_duty) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
_current_pwm_duty = duty;
|
_current_pwm_duty = duty;
|
||||||
|
|
||||||
if (_invert_pwm) {
|
ledcSetDuty(_pwm_chan_num, duty);
|
||||||
duty = (1 << _pwm_precision) - duty;
|
|
||||||
}
|
|
||||||
|
|
||||||
//ledcWrite(_pwm_chan_num, duty);
|
|
||||||
|
|
||||||
// This was ledcWrite, but this is called from an ISR
|
|
||||||
// and ledcWrite uses RTOS features not compatible with ISRs
|
|
||||||
LEDC.channel_group[0].channel[0].duty.duty = duty << 4;
|
|
||||||
bool on = !!duty;
|
|
||||||
LEDC.channel_group[0].channel[0].conf0.sig_out_en = on;
|
|
||||||
LEDC.channel_group[0].channel[0].conf1.duty_start = on;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@@ -49,7 +49,6 @@ namespace Spindles {
|
|||||||
|
|
||||||
void group(Configuration::HandlerBase& handler) override {
|
void group(Configuration::HandlerBase& handler) override {
|
||||||
handler.item("pwm_freq", _pwm_freq);
|
handler.item("pwm_freq", _pwm_freq);
|
||||||
handler.item("invert_pwm", _invert_pwm);
|
|
||||||
|
|
||||||
OnOff::group(handler);
|
OnOff::group(handler);
|
||||||
}
|
}
|
||||||
@@ -62,10 +61,11 @@ namespace Spindles {
|
|||||||
protected:
|
protected:
|
||||||
int32_t _current_pwm_duty;
|
int32_t _current_pwm_duty;
|
||||||
uint8_t _pwm_chan_num;
|
uint8_t _pwm_chan_num;
|
||||||
uint32_t _pwm_freq = 5000;
|
|
||||||
uint32_t _pwm_period; // how many counts in 1 period
|
uint32_t _pwm_period; // how many counts in 1 period
|
||||||
uint8_t _pwm_precision; // auto calculated
|
uint8_t _pwm_precision; // auto calculated
|
||||||
bool _invert_pwm = false;
|
|
||||||
|
// Configurable
|
||||||
|
uint32_t _pwm_freq = 5000;
|
||||||
|
|
||||||
virtual void set_output(uint32_t duty) override;
|
virtual void set_output(uint32_t duty) override;
|
||||||
virtual void deinit();
|
virtual void deinit();
|
||||||
|
Reference in New Issue
Block a user