Skip to content

Commit

Permalink
Merge pull request #47 from simplefoc/dev
Browse files Browse the repository at this point in the history
1.0.8 release PR
  • Loading branch information
runger1101001 authored Jul 21, 2024
2 parents bfd07bd + c8174f5 commit f7a91fa
Show file tree
Hide file tree
Showing 25 changed files with 973 additions and 56 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
.project
.DS_Store
src/encoders/esp32hwencoder.bak/
34 changes: 21 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,20 +10,13 @@ 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 July 2024, for Simple FOC 2.3.4 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?
- 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+)


## What is included
Expand All @@ -48,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.
Expand Down Expand Up @@ -120,6 +116,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
Expand Down
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=SimpleFOCDrivers
version=1.0.7
version=1.0.8
author=Simplefoc <[email protected]>
maintainer=Simplefoc <[email protected]>
sentence=A library of supporting drivers for SimpleFOC. Motor drivers chips, encoder chips, current sensing and supporting code.
Expand Down
1 change: 1 addition & 0 deletions src/comms/SimpleFOCRegisters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
15 changes: 14 additions & 1 deletion src/drivers/simplefocnano/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ void loop(){
}
```

### Additional functions

There are some extra features, you can check for faults, and clear the fault state:

```c++
Expand All @@ -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!*
Expand All @@ -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);
```
```

## 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)
9 changes: 5 additions & 4 deletions src/encoders/a1334/A1334.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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;
};

6 changes: 3 additions & 3 deletions src/encoders/aeat8800q24/AEAT8800Q24.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
9 changes: 5 additions & 4 deletions src/encoders/as5047/AS5047.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down
17 changes: 9 additions & 8 deletions src/encoders/as5047u/AS5047U.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand All @@ -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);

Expand Down
9 changes: 5 additions & 4 deletions src/encoders/as5048a/AS5048A.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down
14 changes: 7 additions & 7 deletions src/encoders/as5600/AS5600.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};


Expand All @@ -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;
};


Expand Down
Loading

0 comments on commit f7a91fa

Please sign in to comment.