From 17be3a521c7a56cc9219d74ee7442b0b2018684f Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Fri, 29 Mar 2024 18:41:41 +0100 Subject: [PATCH 01/13] update README for next release --- README.md | 27 +++++++++++++++------------ library.properties | 2 +- 2 files changed, 16 insertions(+), 13 deletions(-) diff --git a/README.md b/README.md index 8f49c26..fd59a5c 100644 --- a/README.md +++ b/README.md @@ -10,20 +10,11 @@ The intent is to keep the core of SimpleFOC clean, and thus easy to maintain, un ## New Release -v1.0.7 - Released 29 March 2024, for Simple FOC 2.3.2 or later +v1.0.8 - Released ??? 2024, for Simple FOC 2.3.3 or later -What's changed since 1.0.6? -- Improvements to LinearHall driver, thanks to dekutree -- Fix for ESP32 compiler warning, thanks to Yannik Stradmann -- Added STM32 LPTIM encoder driver -- Refactored communications code -- Working telemetry abstraction -- Working streams communications, ASCII based -- Refactored settings storage code -- Refactored I2CCommander -- New utility class for simple trapezoidal motion profiles -- Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=milestone%3A1.0.7+) +What's changed since 1.0.7? +- Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=milestone%3A1.0.8+) ## What is included @@ -120,6 +111,18 @@ Find out more information about the Arduino SimpleFOC project on the [docs websi ## Release History +What's changed since 1.0.6? +- Improvements to LinearHall driver, thanks to dekutree +- Fix for ESP32 compiler warning, thanks to Yannik Stradmann +- Added STM32 LPTIM encoder driver +- Refactored communications code +- Working telemetry abstraction +- Working streams communications, ASCII based +- Refactored settings storage code +- Refactored I2CCommander +- New utility class for simple trapezoidal motion profiles +- Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=milestone%3A1.0.7+) + What's changed since 1.0.5? - Added STSPIN32G4 driver - Added STM32G4 CORDIC code, for greatly accellerated trig functions on supported MCUs diff --git a/library.properties b/library.properties index 94db11b..30a9c8d 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=SimpleFOCDrivers -version=1.0.7 +version=1.0.8 author=Simplefoc maintainer=Simplefoc sentence=A library of supporting drivers for SimpleFOC. Motor drivers chips, encoder chips, current sensing and supporting code. From 69287afcae0442aa6b39f89801668701d2299e84 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Fri, 10 May 2024 10:16:56 +0200 Subject: [PATCH 02/13] fix SPI operation order #43 --- src/encoders/a1334/A1334.cpp | 9 +++++---- src/encoders/aeat8800q24/AEAT8800Q24.cpp | 6 +++--- src/encoders/as5047/AS5047.cpp | 9 +++++---- src/encoders/as5047u/AS5047U.cpp | 17 +++++++++-------- src/encoders/as5048a/AS5048A.cpp | 9 +++++---- src/encoders/mt6816/MT6816.cpp | 4 ++-- 6 files changed, 29 insertions(+), 25 deletions(-) diff --git a/src/encoders/a1334/A1334.cpp b/src/encoders/a1334/A1334.cpp index 85a4e11..23a7696 100644 --- a/src/encoders/a1334/A1334.cpp +++ b/src/encoders/a1334/A1334.cpp @@ -17,9 +17,10 @@ A1334::~A1334() { void A1334::init(SPIClass* _spi) { spi = _spi; - if (nCS>=0) + if (nCS>=0) { pinMode(nCS, OUTPUT); - digitalWrite(nCS, HIGH); + digitalWrite(nCS, HIGH); + } //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices spi->begin(); readRawAngle(); // read an angle @@ -42,13 +43,13 @@ A1334Angle A1334::readRawAngle() { uint16_t A1334::spi_transfer16(uint16_t outdata) { + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); uint16_t result = spi->transfer16(outdata); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); return result; }; diff --git a/src/encoders/aeat8800q24/AEAT8800Q24.cpp b/src/encoders/aeat8800q24/AEAT8800Q24.cpp index 8be3bd5..9331438 100644 --- a/src/encoders/aeat8800q24/AEAT8800Q24.cpp +++ b/src/encoders/aeat8800q24/AEAT8800Q24.cpp @@ -78,14 +78,14 @@ void AEAT8800Q24::setConf2(AEAT8800Q24_CONF2_t value){ uint16_t AEAT8800Q24::transfer16SPI(uint16_t outValue) { // delay 1us between switching the CS line to SPI delayMicroseconds(1); - if (nCS >= 0) - digitalWrite(nCS, LOW); spi->endTransaction(); spi->beginTransaction(spiSettings); + if (nCS >= 0) + digitalWrite(nCS, LOW); uint16_t value = spi->transfer16(outValue); - spi->endTransaction(); if (nCS >= 0) digitalWrite(nCS, HIGH); + spi->endTransaction(); // delay 1us between switching the CS line to SSI delayMicroseconds(1); spi->beginTransaction(ssiSettings); diff --git a/src/encoders/as5047/AS5047.cpp b/src/encoders/as5047/AS5047.cpp index 9455775..f3b4305 100644 --- a/src/encoders/as5047/AS5047.cpp +++ b/src/encoders/as5047/AS5047.cpp @@ -17,9 +17,10 @@ AS5047::~AS5047() { void AS5047::init(SPIClass* _spi) { spi = _spi; - if (nCS>=0) + if (nCS>=0) { pinMode(nCS, OUTPUT); - digitalWrite(nCS, HIGH); + digitalWrite(nCS, HIGH); + } //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices spi->begin(); readRawAngle(); // read an angle @@ -230,13 +231,13 @@ uint16_t AS5047::calcParity(uint16_t data){ uint16_t AS5047::spi_transfer16(uint16_t outdata) { + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); uint16_t result = spi->transfer16(outdata); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); // TODO check parity errorflag = ((result&AS5047_ERRFLG)>0); return result; diff --git a/src/encoders/as5047u/AS5047U.cpp b/src/encoders/as5047u/AS5047U.cpp index bfe70be..00a1f36 100644 --- a/src/encoders/as5047u/AS5047U.cpp +++ b/src/encoders/as5047u/AS5047U.cpp @@ -17,9 +17,10 @@ AS5047U::~AS5047U() { void AS5047U::init(SPIClass* _spi) { spi = _spi; - if (nCS>=0) + if (nCS>=0) { pinMode(nCS, OUTPUT); - digitalWrite(nCS, HIGH); + digitalWrite(nCS, HIGH); + } //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices spi->begin(); readRawAngle(); // read an angle @@ -291,13 +292,13 @@ uint16_t AS5047U::nop16(){ uint16_t AS5047U::spi_transfer16(uint16_t outdata) { + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); uint16_t result = spi->transfer16(outdata); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); errorflag = ((result&AS5047U_ERROR)>0); warningflag = ((result&AS5047U_WARNING)>0); return result; @@ -321,26 +322,26 @@ uint16_t AS5047U::writeRegister24(uint16_t reg, uint16_t data) { buff[0] = (reg>>8)&0x3F; buff[1] = reg&0xFF; buff[2] = calcCRC(reg); + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); spi->transfer(buff, 3); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); errorflag = ((buff[0]&0x40)>0); warningflag = ((buff[0]&0x80)>0); buff[0] = (data>>8)&0x3F; buff[1] = data&0xFF; buff[2] = calcCRC(data); + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); spi->transfer(buff, 3); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); errorflag = ((buff[0]&0x40)>0); warningflag = ((buff[0]&0x80)>0); diff --git a/src/encoders/as5048a/AS5048A.cpp b/src/encoders/as5048a/AS5048A.cpp index 27ef254..b66f968 100644 --- a/src/encoders/as5048a/AS5048A.cpp +++ b/src/encoders/as5048a/AS5048A.cpp @@ -17,9 +17,10 @@ AS5048A::~AS5048A() { void AS5048A::init(SPIClass* _spi) { spi = _spi; - if (nCS>=0) + if (nCS>=0) { pinMode(nCS, OUTPUT); - digitalWrite(nCS, HIGH); + digitalWrite(nCS, HIGH); + } //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices spi->begin(); readRawAngle(); // read an angle @@ -103,13 +104,13 @@ uint16_t AS5048A::nop(){ } uint16_t AS5048A::spi_transfer16(uint16_t outdata) { + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); uint16_t result = spi->transfer16(outdata); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); // TODO check parity errorflag = ((result&AS5048A_ERRFLG)>0); return result; diff --git a/src/encoders/mt6816/MT6816.cpp b/src/encoders/mt6816/MT6816.cpp index d874bad..fec02d0 100644 --- a/src/encoders/mt6816/MT6816.cpp +++ b/src/encoders/mt6816/MT6816.cpp @@ -44,13 +44,13 @@ bool MT6816::parityCheck(uint16_t data) { } uint16_t MT6816::spi_transfer16(uint16_t outdata) { + spi->beginTransaction(settings); if (nCS>=0) digitalWrite(nCS, 0); - spi->beginTransaction(settings); uint16_t result = spi->transfer16(outdata); - spi->endTransaction(); if (nCS>=0) digitalWrite(nCS, 1); + spi->endTransaction(); return result; } From 52b754db17f22725bd9a06737af7d325dde64b21 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Fri, 10 May 2024 10:17:08 +0200 Subject: [PATCH 03/13] fix warnings --- src/settings/rp2040/RP2040FlashSettingsStorage.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/settings/rp2040/RP2040FlashSettingsStorage.cpp b/src/settings/rp2040/RP2040FlashSettingsStorage.cpp index 8bd025e..7c6e2ff 100644 --- a/src/settings/rp2040/RP2040FlashSettingsStorage.cpp +++ b/src/settings/rp2040/RP2040FlashSettingsStorage.cpp @@ -81,15 +81,18 @@ RegisterIO& RP2040FlashSettingsStorage::operator>>(uint32_t& value) { RegisterIO& RP2040FlashSettingsStorage::operator<<(uint8_t value) { - + // TODO implement me! + return *this; }; RegisterIO& RP2040FlashSettingsStorage::operator<<(float value) { - + // TODO implement me! + return *this; }; RegisterIO& RP2040FlashSettingsStorage::operator<<(uint32_t value) { - + // TODO implement me! + return *this; }; #endif \ No newline at end of file From 855e110c2fc747a2fed5524d2594f57caf2f6948 Mon Sep 17 00:00:00 2001 From: mcells <33664753+mcells@users.noreply.github.com> Date: Sun, 19 May 2024 14:00:52 +0200 Subject: [PATCH 04/13] Add ESP32 Hardware Encoder Class - squashed --- .../esp32hwencoder/ESP32HWEncoder.cpp | 198 ++++++++++++++++++ src/encoders/esp32hwencoder/ESP32HWEncoder.h | 66 ++++++ src/encoders/esp32hwencoder/README.md | 49 +++++ 3 files changed, 313 insertions(+) create mode 100644 src/encoders/esp32hwencoder/ESP32HWEncoder.cpp create mode 100644 src/encoders/esp32hwencoder/ESP32HWEncoder.h create mode 100644 src/encoders/esp32hwencoder/README.md diff --git a/src/encoders/esp32hwencoder/ESP32HWEncoder.cpp b/src/encoders/esp32hwencoder/ESP32HWEncoder.cpp new file mode 100644 index 0000000..29fcb9c --- /dev/null +++ b/src/encoders/esp32hwencoder/ESP32HWEncoder.cpp @@ -0,0 +1,198 @@ +#include "ESP32HWEncoder.h" + +#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) + + + +ESP32HWEncoder::ESP32HWEncoder(int pinA, int pinB, int32_t ppr, int pinI) +{ + #ifdef USE_ARDUINO_PINOUT + // Handle Arduino Nano ESP32 quirks with the pin assignments + _pinA = digitalPinToGPIO(pinA); + _pinB = digitalPinToGPIO(pinB); + _pinI = digitalPinToGPIO(pinI); + #else + _pinA = pinA; + _pinB = pinB; + _pinI = pinI; + #endif + + cpr = ppr * 4; // 4x for quadrature + + pcnt_config.ctrl_gpio_num = _pinA; + pcnt_config.pulse_gpio_num = _pinB; + pcnt_config.counter_l_lim = INT16_MIN; + pcnt_config.counter_h_lim = INT16_MAX; +} + +// Interrupt handler for accumulating the pulsecounter count +void IRAM_ATTR overflowCounter(void* arg) +{ + uint8_t interruptStatus = PCNT.int_st.val; + for (uint32_t i = 0; i < 8; i++) + { + if (interruptStatus & BIT(i)) + { + int32_t set = ((overflowISR_args_t*) arg)[i].set; + if(set != 1){ continue;} + int32_t* count = ((overflowISR_args_t*) arg)[i].angleoverflow_val; + + // Add or subtract depending on the direction of the overflow + switch (PCNT.status_unit[i].val) + { + case PCNT_EVT_L_LIM: + *count += INT16_MIN; + break; + case PCNT_EVT_H_LIM: + *count += INT16_MAX; + break; + default: + break; + } + + // Clear the interrupt + PCNT.int_clr.val = BIT(i); + } + } +} + +// Interrupt handler for zeroing the pulsecounter count +void IRAM_ATTR ESP32HWEncoder::indexHandler() + { + pcnt_counter_clear(pcnt_config.unit); + angleOverflow = 0; + indexFound = true; + } + +void ESP32HWEncoder::init() +{ + + // Statically allocate and initialize the spinlock + spinlock = portMUX_INITIALIZER_UNLOCKED; + + // find a free pulsecount unit + for (uint8_t i = 0; i < PCNT_UNIT_MAX; i++) + { + if(cpr > 0){ + inv_cpr = 1.0f/cpr; + } + if(used_units[i] == 0){ + pcnt_config.unit = (pcnt_unit_t) i; + if(pcnt_unit_config(&pcnt_config) == ESP_OK){ + initialized = true; + // Serial.printf("Configured PCNT unit %d\n", i); + used_units[i] = 1; + break; + } + } + + } + if (initialized) + { + // Set up the PCNT peripheral + pcnt_set_pin(pcnt_config.unit, PCNT_CHANNEL_0, pcnt_config.ctrl_gpio_num, pcnt_config.pulse_gpio_num); + pcnt_set_pin(pcnt_config.unit, PCNT_CHANNEL_1, pcnt_config.pulse_gpio_num, pcnt_config.ctrl_gpio_num); + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_0, PCNT_COUNT_INC, PCNT_COUNT_DEC, PCNT_MODE_REVERSE, PCNT_MODE_KEEP); + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_1, PCNT_COUNT_DEC, PCNT_COUNT_INC, PCNT_MODE_REVERSE, PCNT_MODE_KEEP); + + pcnt_counter_pause(pcnt_config.unit); + pcnt_counter_clear(pcnt_config.unit); + + // Select interrupt on reaching high and low counter limit + pcnt_event_enable(pcnt_config.unit, PCNT_EVT_L_LIM); + pcnt_event_enable(pcnt_config.unit, PCNT_EVT_H_LIM); + + // Pass pointer to the angle accumulator and the current PCNT unit to the ISR + overflowISR_args[pcnt_config.unit].angleoverflow_val = &angleOverflow; + overflowISR_args[pcnt_config.unit].unit = pcnt_config.unit; + overflowISR_args[pcnt_config.unit].set = 1; + + // Register and enable the interrupt + pcnt_isr_register(overflowCounter, (void*)&overflowISR_args, 0, (pcnt_isr_handle_t*) NULL); + pcnt_intr_enable(pcnt_config.unit); + + // Just check the last command for errors + if(pcnt_counter_resume(pcnt_config.unit) != ESP_OK){ + initialized = false; + } + + // If an index Pin is defined, create an ISR to zero the angle when the index fires + if (hasIndex()) + { + attachInterrupt(static_cast(_pinI), std::bind(&ESP32HWEncoder::indexHandler,this), RISING); + } + + // Optionally use pullups + if (pullup == USE_INTERN) + { + pinMode(static_cast(_pinA), INPUT_PULLUP); + pinMode(static_cast(_pinB), INPUT_PULLUP); + if (hasIndex()) {pinMode(static_cast(_pinI), INPUT_PULLUP);} + } + + } + +} + +int ESP32HWEncoder::needsSearch() +{ + return !((indexFound && hasIndex()) || !hasIndex()); +} + +int ESP32HWEncoder::hasIndex() +{ + return _pinI != -1; +} + +void ESP32HWEncoder::setCpr(int32_t ppr){ + cpr = 4*ppr; + if(cpr > 0){ + inv_cpr = 1.0f/cpr; // Precalculate the inverse of cpr to avoid "slow" float divisions + } +} + +int32_t ESP32HWEncoder::getCpr(){ + return cpr; +} + +// Change to Step/Dir counting mode. A->Step, B->Dir +void ESP32HWEncoder::setStepDirMode(){ + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_0, PCNT_COUNT_INC, PCNT_COUNT_DIS, PCNT_MODE_KEEP, PCNT_MODE_KEEP); + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_1, PCNT_COUNT_DIS, PCNT_COUNT_DIS, PCNT_MODE_KEEP, PCNT_MODE_REVERSE); +} + +// Change to default AB (quadrature) mode +void ESP32HWEncoder::setQuadratureMode(){ + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_0, PCNT_COUNT_INC, PCNT_COUNT_DEC, PCNT_MODE_REVERSE, PCNT_MODE_KEEP); + pcnt_set_mode(pcnt_config.unit, PCNT_CHANNEL_1, PCNT_COUNT_DEC, PCNT_COUNT_INC, PCNT_MODE_REVERSE, PCNT_MODE_KEEP); +} + +float IRAM_ATTR ESP32HWEncoder::getSensorAngle() +{ + if(!initialized){return -1.0f;} + + taskENTER_CRITICAL(&spinlock); + // We are now in a critical section to prevent interrupts messing with angleOverflow and angleCounter + + // Retrieve the count register into a variable + pcnt_get_counter_value(pcnt_config.unit, &angleCounter); + + // Trim the accumulator variable to prevent issues with it overflowing + // Make the % operand behave mathematically correct (-5 modulo 4 == 3; -5 % 4 == -1) + angleOverflow %= cpr; + if (angleOverflow < 0){ + angleOverflow += cpr; + } + + angleSum = (angleOverflow + angleCounter) % cpr; + if (angleSum < 0) { + angleSum += cpr; + } + + taskEXIT_CRITICAL(&spinlock); // Exit critical section + + // Calculate the shaft angle + return _2PI * angleSum * inv_cpr; +} + +#endif \ No newline at end of file diff --git a/src/encoders/esp32hwencoder/ESP32HWEncoder.h b/src/encoders/esp32hwencoder/ESP32HWEncoder.h new file mode 100644 index 0000000..ad3a42f --- /dev/null +++ b/src/encoders/esp32hwencoder/ESP32HWEncoder.h @@ -0,0 +1,66 @@ + +#pragma once + +#include + + +#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) + +#include "driver/pcnt.h" +#include "soc/pcnt_struct.h" +#include "common/base_classes/Sensor.h" +#include "common/foc_utils.h" +#include "FunctionalInterrupt.h" + +static struct overflowISR_args_t { + int32_t* angleoverflow_val; + pcnt_unit_t unit; + int32_t set; +}overflowISR_args[PCNT_UNIT_MAX]; + +// Statically allocate and initialize a spinlock +static portMUX_TYPE spinlock; +static int used_units[PCNT_UNIT_MAX]; + +class ESP32HWEncoder : public Sensor{ + public: + /** + Encoder class constructor + @param ppr impulses per rotation (cpr=ppr*4) + */ + explicit ESP32HWEncoder(int pinA, int pinB, int32_t ppr, int pinI=-1); + + void init() override; + int needsSearch() override; + int hasIndex(); + float getSensorAngle() override; + void setCpr(int32_t ppr); + int32_t getCpr(); + void setStepDirMode(); + void setQuadratureMode(); + bool initialized = false; + + Pullup pullup; //!< Configuration parameter internal or external pullups + + + + protected: + + + void IRAM_ATTR indexHandler(); + + bool indexFound = false; + + int _pinA, _pinB, _pinI; + + pcnt_config_t pcnt_config; + + int16_t angleCounter; // Stores the PCNT value + int32_t angleOverflow; // In case the PCNT peripheral overflows, this accumulates the max count to keep track of large counts/angles (>= 16 Bit). On index, this gets reset. + int32_t angleSum; // Sum of Counter and Overflow in range [0,cpr] + + int32_t cpr; // Counts per rotation = 4 * ppr for quadrature encoders + float inv_cpr; +}; + +#endif \ No newline at end of file diff --git a/src/encoders/esp32hwencoder/README.md b/src/encoders/esp32hwencoder/README.md new file mode 100644 index 0000000..c6a7033 --- /dev/null +++ b/src/encoders/esp32hwencoder/README.md @@ -0,0 +1,49 @@ +# SimpleFOC Driver for ESP32 hardware encoder + +This encoder driver uses the ESP32´s dedicated pulse counter hardware to efficiently count the AB(I) signals of an encoder. It also supports a Step/Dir-type mode. + +Because most of the counting is done by the peripheral, it should support much higher speeds in comparison to the generic interrupt-based encoder implementation provided in the main library. +The PCNT peripheral can count at several MHz and should not be a limiting factor here. + +You can use encoders with cpr of up to 31 bits. (At this resolution, you would get about 100 counts per second if you mounted such a sensor on the earths rotational axis. Thats plenty ;-) ) + + +## Status + +Seems to work fine! Step/Dir mode is untested. + +## Hardware Setup + +You can connect the encoder to any digital input pin of the ESP32, as they all support the PCNT peripheral. + +## Configuration + +This is a near drop-in replacement for the standard encoder class: + +```c++ +#include "Arduino.h" +#include "SimpleFOC.h" +#include "SimpleFOCDrivers.h" +#include "encoders/esp32hwencoder/ESP32HWEncoder.h" + +#define ENCODER_PPR 4711 +#define ENCODER_PIN_A 16 +#define ENCODER_PIN_B 17 +#define ENCODER_PIN_I 21 + +ESP32HWEncoder encoder = ESP32HWEncoder(ENCODER_PIN_A, ENCODER_PIN_B, ENCODER_PPR, ENCODER_PIN_I); // The Index pin can be omitted + +void setup() { + encoder.pullup = Pullup::USE_INTERN; // optional: pullups + + encoder.setStepDirMode(); // optional: set Stepper type step/dir mode + + encoder.init(); +} + +void loop() { + encoder.update(); // optional: Update manually if not using loopfoc() + + encoder.getAngle() // Access the sensor value +} +``` \ No newline at end of file From 9952f3bdc8fa8a513a5a5aba04fe8fea3ecc9f27 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Sat, 1 Jun 2024 15:11:57 +0200 Subject: [PATCH 05/13] add missing velocity register --- src/comms/SimpleFOCRegisters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/comms/SimpleFOCRegisters.cpp b/src/comms/SimpleFOCRegisters.cpp index d83523e..c91feeb 100644 --- a/src/comms/SimpleFOCRegisters.cpp +++ b/src/comms/SimpleFOCRegisters.cpp @@ -642,6 +642,7 @@ uint8_t SimpleFOCRegisters::sizeOfRegister(uint8_t reg){ case SimpleFOCRegister::REG_CURD_LPF_T: case SimpleFOCRegister::REG_VOLTAGE_LIMIT: case SimpleFOCRegister::REG_CURRENT_LIMIT: + case SimpleFOCRegister::REG_VELOCITY_LIMIT: case SimpleFOCRegister::REG_DRIVER_VOLTAGE_LIMIT: case SimpleFOCRegister::REG_DRIVER_VOLTAGE_PSU: case SimpleFOCRegister::REG_VOLTAGE_SENSOR_ALIGN: From ff2fb846c3b1772e5c9607dc7a9a99dc0060f151 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Mon, 3 Jun 2024 20:16:00 +0200 Subject: [PATCH 06/13] update simplefocnanodriver docs --- .gitignore | 1 + src/drivers/simplefocnano/README.md | 15 ++++++++++++++- 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index ce7f6d0..05e25f4 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,3 @@ .project .DS_Store +src/encoders/esp32hwencoder.bak/ diff --git a/src/drivers/simplefocnano/README.md b/src/drivers/simplefocnano/README.md index 70d2283..596a5ad 100644 --- a/src/drivers/simplefocnano/README.md +++ b/src/drivers/simplefocnano/README.md @@ -31,6 +31,8 @@ void loop(){ } ``` +### Additional functions + There are some extra features, you can check for faults, and clear the fault state: ```c++ @@ -50,6 +52,8 @@ if (driver.isSleeping()) driver.wake(); ``` +### Bus Voltage Sense + As shown in the example you can read the bus voltage: :warning: *this is a slow function. Do not call it while motor is running!* @@ -58,8 +62,17 @@ As shown in the example you can read the bus voltage: float val = driver.getBusVoltage(); // get the bus voltage, in Volts ``` +### SPI port + The driver's nCS pin is 10, and the constant PIN_nCS can be used: ```c++ MagneticSensorAS5048A sensor = MagneticSensorAS5048A(PIN_nCS); -``` \ No newline at end of file +``` + +## Examples + +The following examples for SimpleFOCNanoDriver can be found in our examples directory: + +- [SimpleFOC Nano on AVR](https://github.com/simplefoc/Arduino-FOC-drivers/blob/master/examples/drivers/simplefocnano/simplefocnano_atmega/simplefocnano_atmega.ino) (5V, 10bit ADC range, like original Nano, using AS5048A sensor on SPI) +- [SimpleFOCNanoDriver torque-voltage mode](https://github.com/simplefoc/Arduino-FOC-drivers/blob/master/examples/drivers/simplefocnano/simplefocnano_torque_voltage/simplefocnano_torque_voltage.ino) (3.3V, 12bit ADC range, using AS5048A sensor on SPI) From 79af2736143488861d984760755fb89e5c685cc5 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Wed, 5 Jun 2024 13:21:01 +0200 Subject: [PATCH 07/13] move setting target to beginning of move() --- src/motors/HybridStepperMotor/HybridStepperMotor.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp index f69a252..4b59d83 100644 --- a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp +++ b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp @@ -295,6 +295,10 @@ void HybridStepperMotor::loopFOC() void HybridStepperMotor::move(float new_target) { + // set internal target variable + if (_isset(new_target)) + target = new_target; + // downsampling (optional) if (motion_cnt++ < motion_downsample) return; @@ -315,9 +319,6 @@ void HybridStepperMotor::move(float new_target) if (!enabled) return; - // set internal target variable - if (_isset(new_target)) - target = new_target; // calculate the back-emf voltage if KV_rating available U_bemf = vel*(1/KV) if (_isset(KV_rating)) From 07fbcc9b1b227d581862a6768a60f338f16e279f Mon Sep 17 00:00:00 2001 From: techy-robot Date: Wed, 17 Jul 2024 11:50:30 -0600 Subject: [PATCH 08/13] Added support for MA735 This is largely based off of the code for MA730, with some additional functions to support the variable resolution and speed. The MA735 is probably one of the cheapest Mag Alpha sensors out there. --- src/encoders/ma735/MA735.cpp | 297 ++++++++++++++++++ src/encoders/ma735/MA735.h | 87 +++++ src/encoders/ma735/MagneticSensorMA735.cpp | 26 ++ src/encoders/ma735/MagneticSensorMA735.h | 19 ++ src/encoders/ma735/MagneticSensorMA735SSI.cpp | 34 ++ src/encoders/ma735/MagneticSensorMA735SSI.h | 25 ++ src/encoders/ma735/README.md | 70 +++++ 7 files changed, 558 insertions(+) create mode 100644 src/encoders/ma735/MA735.cpp create mode 100644 src/encoders/ma735/MA735.h create mode 100644 src/encoders/ma735/MagneticSensorMA735.cpp create mode 100644 src/encoders/ma735/MagneticSensorMA735.h create mode 100644 src/encoders/ma735/MagneticSensorMA735SSI.cpp create mode 100644 src/encoders/ma735/MagneticSensorMA735SSI.h create mode 100644 src/encoders/ma735/README.md diff --git a/src/encoders/ma735/MA735.cpp b/src/encoders/ma735/MA735.cpp new file mode 100644 index 0000000..fa5a803 --- /dev/null +++ b/src/encoders/ma735/MA735.cpp @@ -0,0 +1,297 @@ +#include "MA735.h" + +MA735::MA735(SPISettings settings, int nCS) : settings(settings), nCS(nCS) { + +}; +MA735::~MA735() { + +}; + +void MA735::init(SPIClass* _spi) { + spi = _spi; + if (nCS >= 0) { + pinMode(nCS, OUTPUT); + digitalWrite(nCS, HIGH); + } +}; + +float MA735::getCurrentAngle() { + return (readRawAngle() * _2PI)/MA735_16BIT;//It doesn't matter that it is divided by 65536, because the raw angle fills empty data bits with empty zeros so sensor resolution doesn't affect angle calculation +}; // angle in radians, return current value + +uint16_t MA735::readRawAngle() { + uint16_t angle = transfer16(0x0000); + return angle; +}; // 9-13bit angle value + +uint16_t MA735::getZero() { + uint16_t result = readRegister(MA735_REG_ZERO_POSITION_MSB)<<8; + result |= readRegister(MA735_REG_ZERO_POSITION_LSB); + return result; +}; +uint8_t MA735::getBiasCurrentTrimming() { + return readRegister(MA735_REG_BCT); +}; +bool MA735::isBiasCurrrentTrimmingX() { + return (readRegister(MA735_REG_ET) & 0x01)==0x01; +}; +bool MA735::isBiasCurrrentTrimmingY() { + return (readRegister(MA735_REG_ET) & 0x02)==0x02; +}; +uint16_t MA735::getPulsesPerTurn() { + uint16_t result = readRegister(MA735_REG_ILIP_PPT_LSB)>>6; + result |= ((uint16_t)readRegister(MA735_REG_PPT_MSB))<<2; + return result+1; +}; +uint8_t MA735::getIndexLength() { + return (readRegister(MA735_REG_ILIP_PPT_LSB)>>2)&0x0F; +}; +uint8_t MA735::getRotationDirection() { + return (readRegister(MA735_REG_RD)>>7); +}; +uint8_t MA735::getFieldStrengthHighThreshold() { + return (readRegister(MA735_REG_MGLT_MGHT)>>2)&0x07; +}; +uint8_t MA735::getFieldStrengthLowThreshold() { + return (readRegister(MA735_REG_MGLT_MGHT)>>5)&0x07; +}; +FieldStrength MA735::getFieldStrength() { + return (FieldStrength)(readRegister(MA735_REG_MGH_MGL)>>6); +}; +uint8_t MA735::getFilterWindow() { + return readRegister(MA735_REG_FW); +}; +uint8_t MA735::getHysteresis() { + return readRegister(MA735_REG_HYS); +}; +float MA735::getResolution() { + //All I could find in the datasheet was a table with the correlation, no function to convert Filter window to res. + uint8_t reg = readRegister(MA735_REG_FW); + float result; + switch (reg) { + case 51: + result = 9.0; + break; + case 68: + result = 9.5; + break; + case 85: + result = 10.0; + break; + case 102: + result = 10.5; + break; + case 119: + result = 11.0; + break; + case 136: + result = 11.5; + break; + case 153: + result = 12.0; + break; + case 170: + result = 12.5; + break; + case 187: + result = 13.0; + break; + default: + result = 11.0; + break; + } + return result; +}; +int MA735::getUpdateTime() { + //All I could find in the datasheet was a table with the correlation, no function to convert Filter window to update time. + //Returns result in microseconds + uint8_t reg = readRegister(MA735_REG_FW); + int result; + switch (reg) { + case 51: + result = 64; + break; + case 68: + result = 128; + break; + case 85: + result = 256; + break; + case 102: + result = 512; + break; + case 119: + result = 1024; + break; + case 136: + result = 2048; + break; + case 153: + result = 4096; + break; + case 170: + result = 8192; + break; + case 187: + result = 16384; + break; + default: + result = 1024; + break; + } + return result; +}; + + + +void MA735::setZero(uint16_t value) { + writeRegister(MA735_REG_ZERO_POSITION_MSB, value>>8); + writeRegister(MA735_REG_ZERO_POSITION_LSB, value&0x00FF); +}; +void MA735::setBiasCurrentTrimming(uint8_t value) { + writeRegister(MA735_REG_BCT, value); +}; +void MA735::setBiasCurrrentTrimmingEnabled(bool Xenabled, bool Yenabled) { + uint8_t val = Xenabled ? 0x01 : 0x00; + val |= (Yenabled ? 0x02 : 0x00); + writeRegister(MA735_REG_ET, val); +}; +void MA735::setPulsesPerTurn(uint16_t value) { + uint16_t pptVal = value - 1; + writeRegister(MA735_REG_PPT_MSB, pptVal>>2); + uint8_t val = readRegister(MA735_REG_ILIP_PPT_LSB); + val &= 0x3F; + val |= (pptVal&0x03)<<6; + writeRegister(MA735_REG_ILIP_PPT_LSB, val); +}; +void MA735::setIndexLength(uint8_t value) { + uint8_t val = readRegister(MA735_REG_ILIP_PPT_LSB); + val &= 0xC0; + val |= ((value<<2)&0x3F); + writeRegister(MA735_REG_ILIP_PPT_LSB, val); +}; +void MA735::setRotationDirection(uint8_t value) { + if (value==0) + writeRegister(MA735_REG_RD, 0x00); + else + writeRegister(MA735_REG_RD, 0x80); +}; +void MA735::setFieldStrengthThresholds(uint8_t high, uint8_t low) { + uint8_t val = (low<<5) | (high<<2); + writeRegister(MA735_REG_MGLT_MGHT, val); +}; +void MA735::setFilterWindow(uint8_t value) { + writeRegister(MA735_REG_FW, value); +}; +void MA735::setHysteresis(uint8_t value) { + writeRegister(MA735_REG_HYS, value); +}; +void MA735::setResolution(float res) { + //All I could find in the datasheet was a table with the correlation, no function to convert Filter window to res. + uint8_t value; + uint8_t res_int = res * 10;//It has to be a basic type for the switch case + switch (res_int) { + case 90: + value = 51; + break; + case 95: + value = 68; + break; + case 100: + value = 85; + break; + case 105: + value = 102; + break; + case 110: + value = 119; + break; + case 115: + value = 136; + break; + case 120: + value = 153; + break; + case 125: + value = 170; + break; + case 130: + value = 187; + break; + default: + value = 119; + break; + } + writeRegister(MA735_REG_FW, value); +}; +void MA735::setUpdateTime(int microsec) { + //All I could find in the datasheet was a table with the correlation, no function to convert Filter window to update time. + //time in microseconds + uint8_t value; + switch (microsec) { + case 64: + value = 51; + break; + case 128: + value = 68; + break; + case 256: + value = 85; + break; + case 512: + value = 102; + break; + case 1024: + value = 119; + break; + case 2048: + value = 136; + break; + case 4096: + value = 153; + break; + case 8192: + value = 170; + break; + case 16384: + value = 187; + break; + default: + value = 119; + break; + } + writeRegister(MA735_REG_FW, value); +}; + + +uint16_t MA735::transfer16(uint16_t outValue) { + spi->beginTransaction(settings); + if (nCS >= 0) + digitalWrite(nCS, LOW); + uint16_t value = spi->transfer16(outValue); + if (nCS >= 0) + digitalWrite(nCS, HIGH); + spi->endTransaction(); + return value; +}; +uint8_t MA735::readRegister(uint8_t reg) { + uint16_t cmd = 0x4000 | ((reg&0x001F)<<8); + uint16_t value = transfer16(cmd); + delayMicroseconds(1); + value = transfer16(0x0000); + return value>>8; +}; +uint8_t MA735::writeRegister(uint8_t reg, uint8_t value) { + uint8_t write_check = readRegister(reg); + //no need to rewrite, it is the exact same value + if (write_check == value) { + return write_check; + } + else { + uint16_t cmd = 0x8000 | ((reg&0x1F)<<8) | value; + uint16_t result = transfer16(cmd); + delay(20); // 20ms delay required + result = transfer16(0x0000); + return result>>8; + } +}; diff --git a/src/encoders/ma735/MA735.h b/src/encoders/ma735/MA735.h new file mode 100644 index 0000000..77f07b1 --- /dev/null +++ b/src/encoders/ma735/MA735.h @@ -0,0 +1,87 @@ +#ifndef __MA735_H__ +#define __MA735_H__ + + +#include "Arduino.h" +#include "SPI.h" + +enum FieldStrength : uint8_t { + FS_NORMAL = 0x00, + FS_LOW = 0x01, + FS_HIGH = 0x02, + FS_ERR = 0x03 // impossible state +}; + + +#define _2PI 6.28318530718f +#define MA735_16BIT 65536.0f + +#define MA735_REG_ZERO_POSITION_LSB 0x00 +#define MA735_REG_ZERO_POSITION_MSB 0x01 +#define MA735_REG_BCT 0x02 +#define MA735_REG_ET 0x03 +#define MA735_REG_ILIP_PPT_LSB 0x04 +#define MA735_REG_PPT_MSB 0x05 +#define MA735_REG_MGLT_MGHT 0x06 +#define MA735_REG_RD 0x09 +#define MA735_REG_FW 0x0E +#define MA735_REG_HYS 0x10 +#define MA735_REG_MGH_MGL 0x1B + +#define MA735_BITORDER MSBFIRST + +static SPISettings MA735SPISettings(1000000, MA735_BITORDER, SPI_MODE3); // @suppress("Invalid arguments") +static SPISettings MA735SSISettings(4000000, MA735_BITORDER, SPI_MODE1); // @suppress("Invalid arguments") + + +class MA735 { +public: + MA735(SPISettings settings = MA735SPISettings, int nCS = -1); + virtual ~MA735(); + + virtual void init(SPIClass* _spi = &SPI); + + float getCurrentAngle(); // angle in radians, return current value + + uint16_t readRawAngle(); // 9-13bit angle value + uint16_t readRawAngleSSI(); // 9-13bit angle value + + uint16_t getZero(); + uint8_t getBiasCurrentTrimming(); + bool isBiasCurrrentTrimmingX(); + bool isBiasCurrrentTrimmingY(); + uint16_t getPulsesPerTurn(); + uint8_t getIndexLength(); + uint8_t getRotationDirection(); + uint8_t getFieldStrengthHighThreshold(); + uint8_t getFieldStrengthLowThreshold(); + FieldStrength getFieldStrength(); + uint8_t getFilterWindow(); + uint8_t getHysteresis(); + float getResolution(); + int getUpdateTime(); + + void setZero(uint16_t); + void setBiasCurrentTrimming(uint8_t); + void setBiasCurrrentTrimmingEnabled(bool Xenabled, bool Yenabled); + void setPulsesPerTurn(uint16_t); + void setIndexLength(uint8_t); + void setRotationDirection(uint8_t); + void setFieldStrengthThresholds(uint8_t high, uint8_t low); + void setFilterWindow(uint8_t); + void setHysteresis(uint8_t); + void setResolution(float resolution); + void setUpdateTime(int microsec); + +private: + SPIClass* spi; + SPISettings settings; + int nCS = -1; + //float MA735_CPR = 65536.0f; + + uint16_t transfer16(uint16_t outValue); + uint8_t readRegister(uint8_t reg); + uint8_t writeRegister(uint8_t reg, uint8_t value); +}; + +#endif diff --git a/src/encoders/ma735/MagneticSensorMA735.cpp b/src/encoders/ma735/MagneticSensorMA735.cpp new file mode 100644 index 0000000..d16ecf4 --- /dev/null +++ b/src/encoders/ma735/MagneticSensorMA735.cpp @@ -0,0 +1,26 @@ +#include "./MagneticSensorMA735.h" +#include "common/foc_utils.h" +#include "common/time_utils.h" + +MagneticSensorMA735::MagneticSensorMA735(int nCS, SPISettings settings) : MA735(settings, nCS) { + +} + + +MagneticSensorMA735::~MagneticSensorMA735(){ + +} + + +void MagneticSensorMA735::init(SPIClass* _spi) { + this->MA735::init(_spi); + this->Sensor::init(); +} + + +float MagneticSensorMA735::getSensorAngle() { + float angle_data = readRawAngle(); + angle_data = ( angle_data / (float)MA735_16BIT) * _2PI;//It doesn't matter that it is divided by 65536, because the raw angle fills empty data bits with empty zeros so sensor resolution doesn't affect angle calculation + // return the shaft angle + return angle_data; +} diff --git a/src/encoders/ma735/MagneticSensorMA735.h b/src/encoders/ma735/MagneticSensorMA735.h new file mode 100644 index 0000000..36f697d --- /dev/null +++ b/src/encoders/ma735/MagneticSensorMA735.h @@ -0,0 +1,19 @@ +#ifndef __MAGNETIC_SENSOR_MA735_H__ +#define __MAGNETIC_SENSOR_MA735_H__ + + +#include "common/base_classes/Sensor.h" +#include "./MA735.h" + +class MagneticSensorMA735 : public Sensor, public MA735 { +public: + MagneticSensorMA735(int nCS = -1, SPISettings settings = MA735SPISettings); + virtual ~MagneticSensorMA735(); + + virtual float getSensorAngle() override; + + virtual void init(SPIClass* _spi = &SPI); +}; + + +#endif diff --git a/src/encoders/ma735/MagneticSensorMA735SSI.cpp b/src/encoders/ma735/MagneticSensorMA735SSI.cpp new file mode 100644 index 0000000..eaea82e --- /dev/null +++ b/src/encoders/ma735/MagneticSensorMA735SSI.cpp @@ -0,0 +1,34 @@ +#include "./MagneticSensorMA735SSI.h" +#include "common/foc_utils.h" +#include "common/time_utils.h" + +MagneticSensorMA735SSI::MagneticSensorMA735SSI(SPISettings settings) : settings(settings) { + +} + + +MagneticSensorMA735SSI::~MagneticSensorMA735SSI() { + +} + +void MagneticSensorMA735SSI::init(SPIClass* _spi) { + this->spi=_spi; + this->Sensor::init(); +} + +// check 40us delay between each read? +float MagneticSensorMA735SSI::getSensorAngle() { + float angle_data = readRawAngleSSI(); + angle_data = ( angle_data / (float)MA735_16BIT ) * _2PI;//It doesn't matter that it is divided by 65536, because the raw angle fills empty data bits with empty zeros so sensor resolution doesn't affect angle calculation + // return the shaft angle + return angle_data; +} + + +uint16_t MagneticSensorMA735SSI::readRawAngleSSI() { + spi->beginTransaction(settings); + uint16_t value = spi->transfer16(0x0000); + //uint16_t parity = spi->transfer(0x00); + spi->endTransaction(); + return (value<<1); //>>1)&0x3FFF; +}; // 9-13bit angle value diff --git a/src/encoders/ma735/MagneticSensorMA735SSI.h b/src/encoders/ma735/MagneticSensorMA735SSI.h new file mode 100644 index 0000000..37df636 --- /dev/null +++ b/src/encoders/ma735/MagneticSensorMA735SSI.h @@ -0,0 +1,25 @@ +#ifndef __MAGNETIC_SENSOR_MA735SSI_H__ +#define __MAGNETIC_SENSOR_MA735SSI_H__ + + +#include "common/base_classes/Sensor.h" +#include "./MA735.h" + +class MagneticSensorMA735SSI : public Sensor { +public: + MagneticSensorMA735SSI(SPISettings settings = MA735SSISettings); + virtual ~MagneticSensorMA735SSI(); + + virtual float getSensorAngle() override; + + virtual void init(SPIClass* _spi = &SPI); + + uint16_t readRawAngleSSI(); + +private: + SPIClass* spi; + SPISettings settings; +}; + + +#endif diff --git a/src/encoders/ma735/README.md b/src/encoders/ma735/README.md new file mode 100644 index 0000000..d1b402a --- /dev/null +++ b/src/encoders/ma735/README.md @@ -0,0 +1,70 @@ +# MA735 SimpleFOC driver + +This is based on the [MA730](https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/ma730) driver in SimpleFOC, with some tweaks to support the unique registers and options of the MA735. It is a inferior, but less expensive chip after all. + + +## Hardware setup + +Connect as per normal for your SPI bus. No special hardware setup is needed to use this driver. + +## Software setup + +Its actually easier to use than the standard SPI sensor class, because it is less generic: + +```c++ +#include "Arduino.h" +#include "Wire.h" +#include "SPI.h" +#include "SimpleFOC.h" +#include "SimpleFOCDrivers.h" +#include "encoders/ma735/MagneticSensorMA735.h" + +#define SENSOR1_CS 5 // some digital pin that you're using as the nCS pin +MagneticSensorMA735 sensor1(SENSOR1_CS); + + +void setup() { + sensor1.init(); +} +``` + +Set some options: + +```c++ +MagneticSensorMA735 sensor1(SENSOR1_CS, mySPISettings); +``` + +Use another SPI bus: + +```c++ +void setup() { + sensor1.init(&SPI2); +} +``` + +Here's how you can use it: + +```c++ + // update the sensor (only needed if using the sensor without a motor) + sensor1.update(); + + // get the angle, in radians, including full rotations + float a1 = sensor1.getAngle(); + + // get the velocity, in rad/s - note: you have to call getAngle() on a regular basis for it to work + float v1 = sensor1.getVelocity(); + + // get the angle, in radians, no full rotations + float a2 = sensor1.getCurrentAngle(); + + // get the raw 14 bit value + uint16_t raw = sensor1.readRawAngle(); + + // get the field strength + FieldStrength fs = sensor1.getFieldStrength(); + Serial.print("Field strength: "); + Serial.println(fs); + + // set pulses per turn for encoder mode + sensor1.setPulsesPerTurn(999); // set to 999 if we want 1000 PPR == 4000 CPR +``` From 9b895ce8adfcf303e31ab790d2a798082e77a72f Mon Sep 17 00:00:00 2001 From: techy-robot Date: Wed, 17 Jul 2024 12:19:23 -0600 Subject: [PATCH 09/13] Updates README file examples of of use --- src/encoders/ma735/README.md | 26 ++++++++++++++++++++------ 1 file changed, 20 insertions(+), 6 deletions(-) diff --git a/src/encoders/ma735/README.md b/src/encoders/ma735/README.md index d1b402a..eb5f10d 100644 --- a/src/encoders/ma735/README.md +++ b/src/encoders/ma735/README.md @@ -1,6 +1,6 @@ # MA735 SimpleFOC driver -This is based on the [MA730](https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/ma730) driver in SimpleFOC, with some tweaks to support the unique registers and options of the MA735. It is a inferior, but less expensive chip after all. +This is based on the [MA730](https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/ma730) driver in SimpleFOC, with some tweaks to support the unique registers and options of the MA735. It is a little bit inferior, but less expensive chip after all. The advantage however of this chip (besides cost) is that resolution is inversely proportional to reading speed, ranging from 9-13 bit resolution and 64us to 16ms read times. ## Hardware setup @@ -42,6 +42,16 @@ void setup() { } ``` +Set some registers before start +```c++ +void setup() { + sensor1.init(); + + // Note that with this driver there is a write check so registers are not written to if the value is the exact same. Other drivers do not have a write check, and you can easily wear out the NVM every time the code is run. 1,000 cycles max. + sensor1.setResolution(10.0); +} +``` + Here's how you can use it: ```c++ @@ -57,14 +67,18 @@ Here's how you can use it: // get the angle, in radians, no full rotations float a2 = sensor1.getCurrentAngle(); - // get the raw 14 bit value - uint16_t raw = sensor1.readRawAngle(); - // get the field strength FieldStrength fs = sensor1.getFieldStrength(); Serial.print("Field strength: "); Serial.println(fs); - // set pulses per turn for encoder mode - sensor1.setPulsesPerTurn(999); // set to 999 if we want 1000 PPR == 4000 CPR + //get the calculated resolution from FilterWindow register + float res = sensor.getResolution(); + Serial1.print("Resolution: "); + Serial1.println(res); + + //get the calculated update time in micro seconds from the FilterWindow register + int Time = sensor.getUpdateTime(); + Serial1.print("Update Time (microsecs): "); + Serial1.println(Time); ``` From 6a32d47986e19b1d03eef995c44eadd243f2c29b Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sun, 21 Jul 2024 16:19:49 +0200 Subject: [PATCH 10/13] HybridStepperMotor::init() returns int now --- src/motors/HybridStepperMotor/HybridStepperMotor.cpp | 4 ++-- src/motors/HybridStepperMotor/HybridStepperMotor.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp index 4b59d83..63d579d 100644 --- a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp +++ b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp @@ -33,13 +33,13 @@ void HybridStepperMotor::linkDriver(BLDCDriver *_driver) } // init hardware pins -void HybridStepperMotor::init() +int HybridStepperMotor::init() { if (!driver || !driver->initialized) { motor_status = FOCMotorStatus::motor_init_failed; SIMPLEFOC_DEBUG("MOT: Init not possible, driver not initialized"); - return; + return 0; } motor_status = FOCMotorStatus::motor_initializing; SIMPLEFOC_DEBUG("MOT: Init"); diff --git a/src/motors/HybridStepperMotor/HybridStepperMotor.h b/src/motors/HybridStepperMotor/HybridStepperMotor.h index 71e8792..f235ee6 100644 --- a/src/motors/HybridStepperMotor/HybridStepperMotor.h +++ b/src/motors/HybridStepperMotor/HybridStepperMotor.h @@ -42,7 +42,7 @@ class HybridStepperMotor : public FOCMotor BLDCDriver *driver; /** Motor hardware init function */ - void init() override; + int init() override; /** Motor disable function */ void disable() override; /** Motor enable function */ From 3d751cc082f79d442188a99c324b87258ea3b522 Mon Sep 17 00:00:00 2001 From: Candas1 Date: Sun, 21 Jul 2024 16:31:49 +0200 Subject: [PATCH 11/13] Return 1 if successful --- src/motors/HybridStepperMotor/HybridStepperMotor.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp index 63d579d..5755ad8 100644 --- a/src/motors/HybridStepperMotor/HybridStepperMotor.cpp +++ b/src/motors/HybridStepperMotor/HybridStepperMotor.cpp @@ -70,6 +70,7 @@ int HybridStepperMotor::init() _delay(500); motor_status = FOCMotorStatus::motor_uncalibrated; + return 1; } // disable motor driver From c0ed5158a19570b0fa64c2fa16212e0f889532a0 Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Sun, 21 Jul 2024 22:51:51 +0200 Subject: [PATCH 12/13] add correct masks --- src/encoders/as5600/AS5600.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/encoders/as5600/AS5600.cpp b/src/encoders/as5600/AS5600.cpp index fa3449f..c95a6e6 100644 --- a/src/encoders/as5600/AS5600.cpp +++ b/src/encoders/as5600/AS5600.cpp @@ -31,25 +31,25 @@ uint16_t AS5600::angle() { setAngleRegister(); } _wire->requestFrom(_address, (uint8_t)2, (uint8_t)closeTransactions); - result = _wire->read()<<8; + result = (_wire->read()&0x0F)<<8; result |= _wire->read(); return result; }; uint16_t AS5600::readRawAngle() { - return readRegister(AS5600_REG_ANGLE_RAW, 2); + return readRegister(AS5600_REG_ANGLE_RAW, 2) & 0x0FFF; }; uint16_t AS5600::readAngle() { - return readRegister(AS5600_REG_ANGLE, 2); + return readRegister(AS5600_REG_ANGLE, 2) & 0x0FFF; }; uint16_t AS5600::readMagnitude() { - return readRegister(AS5600_REG_MAGNITUDE, 2); + return readRegister(AS5600_REG_MAGNITUDE, 2) & 0x0FFF; }; @@ -74,17 +74,17 @@ AS5600Conf AS5600::readConf() { uint16_t AS5600::readMang() { - return readRegister(AS5600_REG_MANG, 2); + return readRegister(AS5600_REG_MANG, 2) & 0x0FFF; }; uint16_t AS5600::readMPos() { - return readRegister(AS5600_REG_MPOS, 2); + return readRegister(AS5600_REG_MPOS, 2) & 0x0FFF; }; uint16_t AS5600::readZPos() { - return readRegister(AS5600_REG_ZPOS, 2); + return readRegister(AS5600_REG_ZPOS, 2) & 0x0FFF; }; From c8174f511ae30e40870f644df5b756cdd9cbe94a Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Sun, 21 Jul 2024 22:52:19 +0200 Subject: [PATCH 13/13] update README for 1.0.8 release --- README.md | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index fd59a5c..a87a1e1 100644 --- a/README.md +++ b/README.md @@ -10,10 +10,12 @@ The intent is to keep the core of SimpleFOC clean, and thus easy to maintain, un ## New Release -v1.0.8 - Released ??? 2024, for Simple FOC 2.3.3 or later +v1.0.8 - Released July 2024, for Simple FOC 2.3.4 or later What's changed since 1.0.7? +- MA735 driver thanks to [@techyrobot](https://github.com/techy-robot) +- ESP32HWEncoder driver thanks to [@mcells](https://github.com/mcells) - Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=milestone%3A1.0.8+) @@ -39,9 +41,12 @@ Drivers for various position sensor ICs. In many cases these hardware-specific d - [AS5600 I2C driver](src/encoders/as5600/) - I2C driver for the AMS AS5600 and AS5600L absolute position magnetic rotary encoder ICs. - [MA730 SPI driver](src/encoders/ma730/) - SPI driver for the MPS MagAlpha MA730 absolute position magnetic rotary encoder IC. - [MA730 SSI driver](src/encoders/ma730/) - SSI driver for the MPS MagAlpha MA730 absolute position magnetic rotary encoder IC. + - [MA735 SPI driver](src/encoders/ma735/) - SPI driver for the MPS MagAlpha MA735 absolute position magnetic rotary encoder IC. + - [MA735 SSI driver](src/encoders/ma735/) - SSI driver for the MPS MagAlpha MA735 absolute position magnetic rotary encoder IC. - [AS5145 SSI driver](src/encoders/as5145/) - SSI driver for the AMS AS5145 and AS5045 absolute position magnetic rotary encoder ICs. - [TLE5012B SPI driver](src/encoders/tle5012b/) - SPI (half duplex) driver for TLE5012B absolute position magnetic rotary encoder IC. - - [STM32 Hardware Encoder](src/encoders/stm32hwencoder/) - Hardware timer based encoder driver for ABI type quadrature encoders. + - [STM32 Hardware Encoder](src/encoders/stm32hwencoder/) - STM32 Hardware timer based encoder driver for ABI type quadrature encoders. + - [ESP32 Hardware Encoder](src/encoders/esp32hwencoder/) - ESP32 Hardware timer based encoder driver for ABI type quadrature encoders. - [SC60228 SPI driver](src/encoders/sc60228/) - SPI driver for SemiMent SC60288 magnetic encoder IC. - [MA330 SPI driver](src/encoders/ma330/) - SPI driver for the MPS MagAlpha MA330 absolute position magnetic rotary encoder IC. - [MT6816 SPI driver](src/encoders/mt6816/) - SPI driver for the MagnTek MT6816 absolute position magnetic rotary encoder IC.