From 742924c46683ee3a4539d5a6d9d85d8c714a2143 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Tue, 31 Oct 2023 17:13:43 +0100 Subject: [PATCH 1/2] fix #324 to enable more than one HallSensor --- src/sensors/HallSensor.cpp | 1 - src/sensors/HallSensor.h | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/src/sensors/HallSensor.cpp b/src/sensors/HallSensor.cpp index 38767d59..d9e5ec83 100644 --- a/src/sensors/HallSensor.cpp +++ b/src/sensors/HallSensor.cpp @@ -53,7 +53,6 @@ void HallSensor::updateState() { hall_state = new_hall_state; int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state]; - static Direction old_direction; if (new_electric_sector - electric_sector > 3) { //underflow direction = Direction::CCW; diff --git a/src/sensors/HallSensor.h b/src/sensors/HallSensor.h index ad50c7d5..78e1b416 100644 --- a/src/sensors/HallSensor.h +++ b/src/sensors/HallSensor.h @@ -62,6 +62,7 @@ class HallSensor: public Sensor{ // whether last step was CW (+1) or CCW (-1). Direction direction; + Direction old_direction; void attachSectorCallback(void (*onSectorChange)(int a) = nullptr); From 2b18cac1d55dabe3016c33166f5db72369586799 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Tue, 31 Oct 2023 17:20:48 +0100 Subject: [PATCH 2/2] fix StepDirListener PinStatus type problem --- src/communication/StepDirListener.h | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/src/communication/StepDirListener.h b/src/communication/StepDirListener.h index f9691fd3..3627b5e7 100644 --- a/src/communication/StepDirListener.h +++ b/src/communication/StepDirListener.h @@ -5,11 +5,6 @@ #include "../common/foc_utils.h" -#if !defined(TARGET_RP2040) && !defined(_SAMD21_) && !defined(_SAMD51_) && !defined(_SAME51_) && !defined(ARDUINO_UNOR4_WIFI) && !defined(ARDUINO_UNOR4_MINIMA) && !defined(NRF52_SERIES) && !defined(ARDUINO_ARCH_MEGAAVR) -#define PinStatus int -#endif - - /** * Step/Dir listenner class for easier interraction with this communication interface. */ @@ -53,7 +48,7 @@ class StepDirListener int pin_step; //!< step pin int pin_dir; //!< direction pin long count; //!< current counter value - should be set to 0 for homing - PinStatus polarity = RISING; //!< polarity of the step pin + decltype(RISING) polarity = RISING; //!< polarity of the step pin private: float* attached_variable = nullptr; //!< pointer to the attached variable