1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-01 02:21:46 +02:00

Used .undefined() and new .defined() consistently

This commit is contained in:
Mitch Bradley
2021-05-20 10:15:13 -10:00
parent ab61f96012
commit 61373732bf
17 changed files with 95 additions and 98 deletions

View File

@@ -28,9 +28,9 @@ void CoolantControl::init() {
static bool init_message = true; // used to show messages only once.
if (init_message) {
if (!flood_.undefined())
if (flood_.defined())
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Flood coolant on pin %s", flood_.name().c_str());
if (!mist_.undefined())
if (mist_.defined())
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Mist coolant on pin %s", mist_.name().c_str());
init_message = false;
}
@@ -46,7 +46,7 @@ CoolantState CoolantControl::get_state() {
CoolantState cl_state = {};
bool pinState;
if (flood_ != Pin::UNDEFINED) {
if (flood_.defined()) {
auto pinState = flood_.read();
#ifdef INVERT_COOLANT_FLOOD_PIN
pinState = !pinState;
@@ -57,7 +57,7 @@ CoolantState CoolantControl::get_state() {
}
}
if (mist_ != Pin::UNDEFINED) {
if (mist_.defined()) {
auto pinState = mist_.read();
#ifdef INVERT_COOLANT_MIST_PIN
pinState = !pinState;
@@ -72,7 +72,7 @@ CoolantState CoolantControl::get_state() {
}
void CoolantControl::write(CoolantState state) {
if (flood_ != Pin::UNDEFINED) {
if (flood_.defined()) {
bool pinState = state.Flood;
#ifdef INVERT_COOLANT_FLOOD_PIN
pinState = !pinState;
@@ -80,7 +80,7 @@ void CoolantControl::write(CoolantState state) {
flood_.write(pinState);
}
if (mist_ != Pin::UNDEFINED) {
if (mist_.defined()) {
bool pinState = state.Mist;
#ifdef INVERT_COOLANT_MIST_PIN
pinState = !pinState;
@@ -126,8 +126,7 @@ void CoolantControl::sync(CoolantState state) {
void CoolantControl::validate() const {}
void CoolantControl::handle(Configuration::HandlerBase& handler)
{
void CoolantControl::handle(Configuration::HandlerBase& handler) {
handler.handle("flood", flood_);
handler.handle("mist", mist_);
}

View File

@@ -32,11 +32,12 @@ class CoolantControl : public Configuration::Configurable {
Pin flood_;
void write(CoolantState state);
public:
CoolantControl() = default;
bool hasMist() const { return mist_ != Pin::UNDEFINED; }
bool hasFlood() const { return flood_ != Pin::UNDEFINED; }
bool hasMist() const { return mist_.defined(); }
bool hasFlood() const { return flood_.defined(); }
// Initializes coolant control pins.
void init();

View File

@@ -118,7 +118,7 @@ void limits_go_home(uint8_t cycle_mask) {
}
// Set search mode with approach at seek rate to quickly engage the specified cycle_mask limit switches.
bool approach = true;
float homing_rate = homing_seek_rate->get(); // TODO FIXME: in YAML this is per-axis. We should move this into the loop.
float homing_rate = homing_seek_rate->get(); // TODO FIXME: in YAML this is per-axis. We should move this into the loop.
uint8_t n_active_axis;
AxisMask limit_state, axislock;
do {
@@ -243,7 +243,7 @@ void limits_go_home(uint8_t cycle_mask) {
auto pulloff = homing_pulloff->get();
for (uint8_t idx = 0; idx < n_axis; idx++) {
Axis* axisConf = MachineConfig::instance()->_axes->_axis[idx];
auto homing = axisConf->_homing;
auto homing = axisConf->_homing;
auto steps = axisConf->_stepsPerMm;
if (cycle_mask & bit(idx)) {
float travel = axisConf->_maxTravel;
@@ -273,7 +273,7 @@ void limits_init() {
for (int axis = 0; axis < n_axis; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = MachineConfig::instance()->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && !gangConfig->_endstops->_dual.undefined()) {
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
#ifndef DISABLE_LIMIT_PIN_PULL_UP
@@ -316,7 +316,7 @@ void limits_disable() {
for (int axis = 0; axis < n_axis; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = MachineConfig::instance()->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && !gangConfig->_endstops->_dual.undefined()) {
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
pin.detachInterrupt();
}
@@ -333,7 +333,7 @@ AxisMask limits_get_state() {
for (int axis = 0; axis < n_axis; axis++) {
for (int gang_index = 0; gang_index < 2; gang_index++) {
auto gangConfig = MachineConfig::instance()->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr && !gangConfig->_endstops->_dual.undefined()) {
if (gangConfig->_endstops != nullptr && gangConfig->_endstops->_dual.defined()) {
Pin& pin = gangConfig->_endstops->_dual;
pinMask |= (pin.read() << axis);
}
@@ -393,19 +393,19 @@ void limitCheckTask(void* pvParameters) {
}
float limitsMaxPosition(uint8_t axis) {
auto axisConfig = MachineConfig::instance()->_axes->_axis[axis];
auto homing = axisConfig->_homing;
float mpos = (homing != nullptr) ? homing->_mpos : 0;
auto maxtravel = axisConfig->_maxTravel;
auto axisConfig = MachineConfig::instance()->_axes->_axis[axis];
auto homing = axisConfig->_homing;
float mpos = (homing != nullptr) ? homing->_mpos : 0;
auto maxtravel = axisConfig->_maxTravel;
return (homing == nullptr || homing->_positiveDirection) ? mpos + maxtravel : mpos;
}
float limitsMinPosition(uint8_t axis) {
auto axisConfig = MachineConfig::instance()->_axes->_axis[axis];
auto homing = axisConfig->_homing;
float mpos = (homing != nullptr) ? homing->_mpos : 0;
auto maxtravel = axisConfig->_maxTravel;
auto axisConfig = MachineConfig::instance()->_axes->_axis[axis];
auto homing = axisConfig->_homing;
float mpos = (homing != nullptr) ? homing->_mpos : 0;
auto maxtravel = axisConfig->_maxTravel;
return (homing == nullptr || homing->_positiveDirection) ? mpos : mpos - maxtravel;
}
@@ -428,12 +428,10 @@ bool __attribute__((weak)) limitsCheckTravel(float* target) {
bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) {
auto gangConfig = MachineConfig::instance()->_axes->_axis[axis]->_gangs[gang_index];
if (gangConfig->_endstops != nullptr)
{
return !gangConfig->_endstops->_dual.undefined();
}
else {
if (gangConfig->_endstops != nullptr) {
return gangConfig->_endstops->_dual.defined();
} else {
return false;
}
}

View File

@@ -18,18 +18,18 @@
// TODO FIXME: Split this file up into several files, perhaps put it in some folder and namespace Machine?
void Endstops::validate() const {
// if (!_dual.undefined()) {
// Assert(_positive.undefined(), "If dual endstops are defined, you cannot also define positive and negative endstops");
// Assert(_negative.undefined(), "If dual endstops are defined, you cannot also define positive and negative endstops");
// }
// if (!_positive.undefined() || !_negative.undefined()) {
// Assert(_positive.undefined(), "If positive or negative endstops are defined, you cannot also define dual endstops");
// }
// if (_dual.defined()) {
// Assert(_positive.undefined(), "If dual endstops are defined, you cannot also define positive and negative endstops");
// Assert(_negative.undefined(), "If dual endstops are defined, you cannot also define positive and negative endstops");
// }
// if (_positive.defined() || _negative.defined()) {
// Assert(_positive.undefined(), "If positive or negative endstops are defined, you cannot also define dual endstops");
// }
}
void Endstops::handle(Configuration::HandlerBase& handler) {
// handler.handle("positive", _positive);
// handler.handle("negative", _negative);
// handler.handle("positive", _positive);
// handler.handle("negative", _negative);
handler.handle("dual", _dual);
handler.handle("hard_limits", _hardLimits);
}
@@ -102,14 +102,13 @@ void Axes::init() {
#ifdef USE_STEPSTICK
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Using StepStick Mode");
if (StepperResetPin->get() != Pin::UNDEFINED) {
if (StepperResetPin->get().defined()) {
// !RESET pin on steppers (MISO On Schematic)
StepperResetPin->get().setAttr(Pin::Attr::Output | Pin::Attr::InitialOn);
}
#endif
if (!_sharedStepperDisable.undefined())
{
if (_sharedStepperDisable.defined()) {
_sharedStepperDisable.setAttr(Pin::Attr::Output);
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Shared stepper disable pin:%s", _sharedStepperDisable.name());
}
@@ -322,10 +321,10 @@ Axes::~Axes() {
}
void I2SOBus::validate() const {
if (!_bck.undefined() || !_data.undefined() || !_ws.undefined()) {
Assert(!_bck.undefined(), "I2SO BCK pin should be configured once.");
Assert(!_data.undefined(), "I2SO Data pin should be configured once.");
Assert(!_ws.undefined(), "I2SO WS pin should be configured once.");
if (_bck.defined() || _data.defined() || _ws.defined()) {
Assert(_bck.defined(), "I2SO BCK pin should be configured once.");
Assert(_data.defined(), "I2SO Data pin should be configured once.");
Assert(_ws.defined(), "I2SO WS pin should be configured once.");
}
}
@@ -336,11 +335,11 @@ void I2SOBus::handle(Configuration::HandlerBase& handler) {
}
void SPIBus::validate() const {
if (!_ss.undefined() || !_miso.undefined() || !_mosi.undefined() || !_sck.undefined()) {
Assert(!_ss.undefined(), "SPI SS pin should be configured once.");
Assert(!_miso.undefined(), "SPI MISO pin should be configured once.");
Assert(!_mosi.undefined(), "SPI MOSI pin should be configured once.");
Assert(!_sck.undefined(), "SPI SCK pin should be configured once.");
if (_ss.defined() || _miso.defined() || _mosi.defined() || _sck.defined()) {
Assert(_ss.defined(), "SPI SS pin should be configured once.");
Assert(_miso.defined(), "SPI MISO pin should be configured once.");
Assert(_mosi.defined(), "SPI MOSI pin should be configured once.");
Assert(_sck.defined(), "SPI SCK pin should be configured once.");
}
}

View File

@@ -67,6 +67,7 @@ public:
inline bool operator!=(const Pin& o) const { return _index != o._index; }
inline bool undefined() const { return (*this) == UNDEFINED; }
inline bool defined() const { return (*this) != UNDEFINED; }
inline uint8_t getNative(Capabilities expectedBehavior) const {
auto detail = Pins::PinLookup::_instance.GetPin(_index);
@@ -89,7 +90,7 @@ public:
detail->setAttr(attributes);
}
inline Attr getAttr() const {
inline Attr getAttr() const {
auto detail = Pins::PinLookup::_instance.GetPin(_index);
return detail->getAttr();
}

View File

@@ -42,7 +42,7 @@ class Probe : public Configuration::Configurable {
public:
Probe() = default;
bool exists() const { return _probePin != Pin::UNDEFINED; }
bool exists() const { return _probePin.defined(); }
// Probe pin initialization routine.
void init();

View File

@@ -144,7 +144,7 @@ SDState get_sd_state(bool refresh) {
SPI.begin(sckPin, misoPin, mosiPin, ssPin); // this will get called for each motor, but does not seem to hurt anything
//no need to go further if SD detect is not correct
if (SDCardDetPin->get() != Pin::UNDEFINED) {
if (SDCardDetPin->get().defined()) {
if (!((SDCardDetPin->get().read() == SDCARD_DET_VAL) ? true : false)) {
sd_state = SDState::NotPresent;
return sd_state;

View File

@@ -34,7 +34,7 @@ namespace Spindles {
_forward_pin = SpindleForwardPin->get();
_reverse_pin = SpindleReversePin->get();
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Spindle output pin not defined");
return; // We cannot continue without the output pin
}
@@ -74,7 +74,7 @@ namespace Spindles {
uint32_t _10v::set_rpm(uint32_t rpm) {
uint32_t pwm_value;
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return rpm;
}
@@ -121,10 +121,10 @@ namespace Spindles {
*/
SpindleState _10v::get_state() {
if (_current_pwm_duty == 0 || _output_pin == Pin::UNDEFINED) {
if (_current_pwm_duty == 0 || _output_pin.undefined()) {
return SpindleState::Disable;
}
if (_direction_pin != Pin::UNDEFINED) {
if (_direction_pin.defined()) {
return _direction_pin.read() ? SpindleState::Cw : SpindleState::Ccw;
}
return SpindleState::Cw;

View File

@@ -54,7 +54,7 @@ namespace Spindles {
void BESC::init() {
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: BESC output pin not defined");
return; // We cannot continue without the output pin
}
@@ -97,7 +97,7 @@ namespace Spindles {
uint32_t BESC::set_rpm(uint32_t rpm) {
uint32_t pwm_value;
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return rpm;
}

View File

@@ -28,7 +28,7 @@ namespace Spindles {
void Dac::init() {
get_pins_and_settings();
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return;
}
@@ -47,7 +47,7 @@ namespace Spindles {
_enable_pin.setAttr(Pin::Attr::Output);
_direction_pin.setAttr(Pin::Attr::Output);
is_reversable = (_direction_pin != Pin::UNDEFINED);
is_reversable = _direction_pin.defined();
use_delays = true;
config_message();
@@ -63,7 +63,7 @@ namespace Spindles {
}
uint32_t Dac::set_rpm(uint32_t rpm) {
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return rpm;
}

View File

@@ -51,7 +51,7 @@ namespace Spindles {
_enable_pin = LaserEnablePin->get();
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: LASER_OUTPUT_PIN not defined");
return; // We cannot continue without the output pin
}

View File

@@ -34,7 +34,7 @@ namespace Spindles {
void PWM::init() {
get_pins_and_settings();
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
grbl_msg_sendf(CLIENT_ALL, MsgLevel::Info, "Warning: Spindle output pin not defined");
return; // We cannot continue without the output pin
}
@@ -75,7 +75,7 @@ namespace Spindles {
_direction_pin = SpindleDirectionPin->get();
is_reversable = (_direction_pin != Pin::UNDEFINED);
is_reversable = _direction_pin.defined();
_pwm_freq = spindle_pwm_freq->get();
_pwm_precision = calc_pwm_precision(_pwm_freq); // detewrmine the best precision
@@ -111,7 +111,7 @@ namespace Spindles {
uint32_t PWM::set_rpm(uint32_t rpm) {
uint32_t pwm_value;
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return rpm;
}
@@ -174,10 +174,10 @@ namespace Spindles {
}
SpindleState PWM::get_state() {
if (_current_pwm_duty == 0 || _output_pin == Pin::UNDEFINED) {
if (_current_pwm_duty == 0 || _output_pin.undefined()) {
return SpindleState::Disable;
}
if (_direction_pin != Pin::UNDEFINED) {
if (_direction_pin.defined()) {
return _direction_pin.read() ? SpindleState::Cw : SpindleState::Ccw;
}
return SpindleState::Cw;
@@ -202,7 +202,7 @@ namespace Spindles {
}
void PWM::set_output(uint32_t duty) {
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return;
}
@@ -228,7 +228,7 @@ namespace Spindles {
}
void PWM::set_enable_pin(bool enable) {
if (_enable_pin == Pin::UNDEFINED) {
if (_enable_pin.undefined()) {
return;
}

View File

@@ -30,7 +30,7 @@ namespace Spindles {
void Relay::init() {
get_pins_and_settings();
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return;
}
@@ -38,7 +38,7 @@ namespace Spindles {
_enable_pin.setAttr(Pin::Attr::Output);
_direction_pin.setAttr(Pin::Attr::Output);
is_reversable = (_direction_pin != Pin::UNDEFINED);
is_reversable = _direction_pin.defined();
use_delays = true;
config_message();
@@ -55,7 +55,7 @@ namespace Spindles {
}
uint32_t Relay::set_rpm(uint32_t rpm) {
if (_output_pin == Pin::UNDEFINED) {
if (_output_pin.undefined()) {
return rpm;
}

View File

@@ -301,19 +301,19 @@ namespace Spindles {
bool pins_settings_ok = true;
_txd_pin = VFDRS485TXDPin->get();
if (_txd_pin == Pin::UNDEFINED) {
if (_txd_pin.undefined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_TXD_PIN");
pins_settings_ok = false;
}
_rxd_pin = VFDRS485RXDPin->get();
if (_rxd_pin == Pin::UNDEFINED) {
if (_rxd_pin.undefined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RXD_PIN");
pins_settings_ok = false;
}
_rts_pin = VFDRS485RTSPin->get();
if (_rts_pin == Pin::UNDEFINED) {
if (_rts_pin.undefined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Undefined VFD_RS485_RTS_PIN");
pins_settings_ok = false;
}

View File

@@ -994,10 +994,9 @@ void IRAM_ATTR Stepper_Timer_Stop() {
bool get_stepper_disable() { // returns true if steppers are disabled
auto axesConfig = MachineConfig::instance()->_axes;
if (!axesConfig->_sharedStepperDisable.undefined()) {
if (axesConfig->_sharedStepperDisable.defined()) {
bool disabled = axesConfig->_sharedStepperDisable.read();
return disabled;
} else {
return false; // thery are never disabled if there is no pin defined
}
return false; // they are never disabled if there is no pin defined
}

View File

@@ -49,7 +49,7 @@ bool debouncing = false; // debouncing in process
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
// setup control inputs
if (ControlSafetyDoorPin->get() != Pin::UNDEFINED) {
if (ControlSafetyDoorPin->get().defined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Door switch on pin %s", ControlSafetyDoorPin->getStringValue());
auto pin = ControlSafetyDoorPin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
@@ -60,7 +60,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (ControlResetPin->get() != Pin::UNDEFINED) {
if (ControlResetPin->get().defined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Reset switch on pin %s", ControlResetPin->getStringValue());
auto pin = ControlResetPin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
@@ -71,7 +71,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (ControlFeedHoldPin->get() != Pin::UNDEFINED) {
if (ControlFeedHoldPin->get().defined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Hold switch on pin %s", ControlFeedHoldPin->getStringValue());
auto pin = ControlFeedHoldPin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
@@ -82,7 +82,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (ControlCycleStartPin->get() != Pin::UNDEFINED) {
if (ControlCycleStartPin->get().defined()) {
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "Start switch on pin %s", ControlCycleStartPin->getStringValue());
auto pin = ControlCycleStartPin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
@@ -93,7 +93,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (MacroButton0Pin->get() != Pin::UNDEFINED) {
if (MacroButton0Pin->get().defined()) {
auto pin = MacroButton0Pin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
@@ -103,7 +103,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (MacroButton1Pin->get() != Pin::UNDEFINED) {
if (MacroButton1Pin->get().defined()) {
auto pin = MacroButton1Pin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
@@ -113,7 +113,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (MacroButton2Pin->get() != Pin::UNDEFINED) {
if (MacroButton2Pin->get().defined()) {
auto pin = MacroButton2Pin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
@@ -123,7 +123,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
pin.attachInterrupt(isr_control_inputs, CHANGE);
}
if (MacroButton3Pin->get() != Pin::UNDEFINED) {
if (MacroButton3Pin->get().defined()) {
auto pin = MacroButton3Pin->get();
auto attr = Pin::Attr::Input | Pin::Attr::ISR;
if (pin.capabilities().has(Pins::PinCapabilities::PullUp)) {
@@ -244,42 +244,42 @@ ControlPins system_control_get_state() {
ControlPins pin_states;
pin_states.value = 0;
defined_pins.bit.safetyDoor = ControlSafetyDoorPin->get() != Pin::UNDEFINED;
defined_pins.bit.safetyDoor = ControlSafetyDoorPin->get().defined();
if (ControlSafetyDoorPin->get().read()) {
pin_states.bit.safetyDoor = true;
}
defined_pins.bit.reset = ControlResetPin->get() != Pin::UNDEFINED;
defined_pins.bit.reset = ControlResetPin->get().defined();
if (ControlResetPin->get().read()) {
pin_states.bit.reset = true;
}
defined_pins.bit.feedHold = ControlFeedHoldPin->get() != Pin::UNDEFINED;
defined_pins.bit.feedHold = ControlFeedHoldPin->get().defined();
if (ControlFeedHoldPin->get().read()) {
pin_states.bit.feedHold = true;
}
defined_pins.bit.cycleStart = ControlCycleStartPin->get() != Pin::UNDEFINED;
defined_pins.bit.cycleStart = ControlCycleStartPin->get().defined();
if (ControlCycleStartPin->get().read()) {
pin_states.bit.cycleStart = true;
}
defined_pins.bit.macro0 = MacroButton0Pin->get() != Pin::UNDEFINED;
defined_pins.bit.macro0 = MacroButton0Pin->get().defined();
if (MacroButton0Pin->get().read()) {
pin_states.bit.macro0 = true;
}
defined_pins.bit.macro1 = MacroButton1Pin->get() != Pin::UNDEFINED;
defined_pins.bit.macro1 = MacroButton1Pin->get().defined();
if (MacroButton1Pin->get().read()) {
pin_states.bit.macro1 = true;
}
defined_pins.bit.macro2 = MacroButton2Pin->get() != Pin::UNDEFINED;
defined_pins.bit.macro2 = MacroButton2Pin->get().defined();
if (MacroButton2Pin->get().read()) {
pin_states.bit.macro2 = true;
}
defined_pins.bit.macro3 = MacroButton3Pin->get() != Pin::UNDEFINED;
defined_pins.bit.macro3 = MacroButton3Pin->get().defined();
if (MacroButton3Pin->get().read()) {
pin_states.bit.macro3 = true;
}

View File

@@ -26,7 +26,7 @@ namespace UserOutput {
_number = number;
_pin = pin;
if (_pin == Pin::UNDEFINED) {
if (_pin.undefined()) {
return;
}
@@ -62,7 +62,7 @@ namespace UserOutput {
_pin = pin;
_pwm_frequency = pwm_frequency;
if (pin == Pin::UNDEFINED) {
if (pin.undefined()) {
return;
}
@@ -104,7 +104,7 @@ namespace UserOutput {
// returns true if able to set value
bool AnalogOutput::set_level(uint32_t numerator) {
// look for errors, but ignore if turning off to prevent mask turn off from generating errors
if (_pin == Pin::UNDEFINED) {
if (_pin.undefined()) {
return false;
}