Skip to content

Commit

Permalink
Merge pull request #42 from simplefoc/dev
Browse files Browse the repository at this point in the history
Release 1.0.7 PR
  • Loading branch information
runger1101001 authored Mar 29, 2024
2 parents 76be538 + 447be3f commit bfd07bd
Show file tree
Hide file tree
Showing 73 changed files with 3,123 additions and 1,167 deletions.
20 changes: 10 additions & 10 deletions .github/workflows/ccpp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ jobs:
strategy:
matrix:
arduino-boards-fqbn:
- arduino:avr:uno # arudino uno
- arduino:avr:nano # arudino nano
- arduino:sam:arduino_due_x # arduino due
- arduino:samd:nano_33_iot # samd21
- adafruit:samd:adafruit_metro_m4 # samd51
Expand All @@ -25,42 +25,42 @@ jobs:
- STMicroelectronics:stm32:Nucleo_64:pnum=NUCLEO_F411RE # stm32 nucleo
- arduino:mbed_rp2040:pico # rpi pico
include:
- arduino-boards-fqbn: arduino:avr:uno
sketches-exclude: calibrated mt6816_spi smoothing
- arduino-boards-fqbn: arduino:avr:nano
sketches-exclude: calibrated mt6816_spi smoothing simplefocnano_torque_voltage
required-libraries: Simple FOC
- arduino-boards-fqbn: arduino:sam:arduino_due_x
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
sketches-exclude: calibrated smoothing simplefocnano_torque_voltage simplefocnano_atmega
- arduino-boards-fqbn: arduino:samd:nano_33_iot
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
- arduino-boards-fqbn: arduino:mbed_rp2040:pico
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
sketches-exclude: calibrated smoothing simplefocnano_torque_voltage simplefocnano_atmega
- arduino-boards-fqbn: adafruit:samd:adafruit_metro_m4
platform-url: https://adafruit.github.io/arduino-board-index/package_adafruit_index.json
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
sketches-exclude: calibrated smoothing simplefocnano_torque_voltage simplefocnano_atmega
# - arduino-boards-fqbn: esp32:esp32:esp32doit-devkit-v1
# platform-url: https://dl.espressif.com/dl/package_esp32_index.json
# required-libraries: Simple FOC
# sketch-names: '**.ino'
- arduino-boards-fqbn: esp32:esp32:esp32 # esp32
platform-url: https://espressif.github.io/arduino-esp32/package_esp32_index.json
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
sketches-exclude: calibrated smoothing simplefocnano_torque_voltage simplefocnano_atmega linearhall
- arduino-boards-fqbn: esp32:esp32:esp32s2 # esp32s2
platform-url: https://espressif.github.io/arduino-esp32/package_esp32_index.json
required-libraries: Simple FOC
sketches-exclude: calibrated smoothing
sketches-exclude: calibrated smoothing simplefocnano_torque_voltage simplefocnano_atmega
- arduino-boards-fqbn: STMicroelectronics:stm32:GenF1:pnum=BLUEPILL_F103C8
platform-url: https://github.com/stm32duino/BoardManagerFiles/raw/main/package_stmicroelectronics_index.json
required-libraries: Simple FOC
sketches-exclude: calibrated mt6816_spi smoothing
sketches-exclude: calibrated mt6816_spi smoothing simplefocnano_torque_voltage simplefocnano_atmega
- arduino-boards-fqbn: STMicroelectronics:stm32:Nucleo_64:pnum=NUCLEO_F411RE
platform-url: https://github.com/stm32duino/BoardManagerFiles/raw/main/package_stmicroelectronics_index.json
required-libraries: Simple FOC
sketches-exclude: smoothing
sketches-exclude: smoothing simplefocnano_torque_voltage simplefocnano_atmega
# Do not cancel all jobs / architectures if one job fails
fail-fast: false
steps:
Expand Down
53 changes: 39 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,27 +10,38 @@ The intent is to keep the core of SimpleFOC clean, and thus easy to maintain, un

## New Release

v1.0.6 - Released December 2023, for Simple FOC 2.3.2 or later
v1.0.7 - Released 29 March 2024, for Simple FOC 2.3.2 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.5?
- Added STSPIN32G4 driver
- Added STM32G4 CORDIC code, for greatly accellerated trig functions on supported MCUs
- Added STM32FlashSettingsStorage driver, supporting STM32G4 MCUs
- Improvements in the MT6835 sensor driver
- Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=is%3Aissue+milestone%3A1.0.6+)

## What is included

What is here? See the sections below. Each driver or function should come with its own more detailed README.

### Motor/Gate driver ICs

Software to control gate driver ICs or integrated driver ICs which have advanced configuration and status interfaces, e.g. via I2C or SPI.

- [TMC6200 driver](src/drivers/tmc6200/) - SPI driver for Trinamics TMC6200 motor driver IC.
- [DRV8316 driver](src/drivers/drv8316/) - SPI driver for TI's DRV8316 motor driver IC.
- [STSPIN32G4 driver](src/drivers/stspin32g4/) - I2C and BLDCDriver for the STSPIN32G4 integrated gate driver MCU.

### Encoders

Drivers for various position sensor ICs. In many cases these hardware-specific drivers often support more functionality than the generic SimpleFOC sensor drivers, including reading status registers, setting configurations and more.

- [AS5048A SPI driver](src/encoders/as5048a/) - SPI driver for the AMS AS5048A absolute position magnetic rotary encoder IC.
- [AS5047 SPI driver](src/encoders/as5047/) - SPI driver for the AMS AS5047P and AS5047D absolute position magnetic rotary encoder ICs.
- [AS5047U SPI driver](src/encoders/as5047u/) - SPI driver for the AMS AS5047U absolute position magnetic rotary encoder ICs.
Expand All @@ -46,21 +57,25 @@ What is here? See the sections below. Each driver or function should come with i
- [MT6701 SSI driver](src/encoders/mt6701/) - SSI driver for the MagnTek MT6701 absolute position magnetic rotary encoder IC.
- [MT6835 SPI driver](src/encoders/mt6835/) - SPI driver for the MagnTek MT6835 21 bit magnetic rotary encoder IC.
- [STM32 PWM sensor driver](src/encoders/stm32pwmsensor/) - STM32 native timer-based driver for PWM angle sensors.
- [CalibratedSensor](src/encoders/calibrated/) - A sensor which can calibrate for eccentricity on the magnet placement.
- [SmoothingSensor](src/encoders/smoothing/) - A SimpleFOC Sensor wrapper implementation which adds angle extrapolation.

### Communications

- [I2CCommander I2C driver](src/comms/i2c/) - I2C communications protocol and drivers for both controller and target devices, based on register abstraction
- [STM32 SpeedDir Input](src/comms/stm32speeddir/) - Control target velocity with PWM speed and direction inputs
- [SerialBinaryCommander](src/comms/serial/) - Serial communications with binary protocol, based on register abstraction
- [Telemetry](src/comms/telemetry/) - Telemetry abstraction, based on registers
- [SerialASCIITelemetry](src/comms/serial/) - Serial communications with ascii protocol, based on register abstraction
Extended communications classes for SimpleFOC. In particular the Telemetry and PacketCommander classes, which implement ASCII or Binary communications and allow monitoring and control of multiple motors, via an easy to use "Registers" abstraction. The Binary and ASCII packet based protocols are directly supported in [PySimpleFOC](https://github.com/simplefoc/pysimplefoc).

- [PacketCommander](src/comms/streams/) - Serial communications with binary protocol, based on register abstraction - get or set any value in SimpleFOC
- [Telemetry](src/comms/telemetry/) - Telemetry based on registers - monitor any value in SimpleFOC, and log in either ASCII or Binary, compatible with PacketCommander
- [SimpleTelemetry](src/comms/telemetry/) - Register telemetry for use with Arduino Serial Plotter tool
- [TeleplotTelemetry](src/comms/telemetry/) - Register telemetry for use with VSCode Teleplot extension
- [I2CCommander I2C driver](src/comms/i2c/) - I2C communications based on register abstraction
- [STM32 SpeedDir Input](src/comms/stm32speeddir/) - Control target velocity with PWM speed and direction inputs

### Settings

Load and store SimpleFOC motor settings, based on register abstraction.
Load and store SimpleFOC motor settings, based on register abstraction. Storing the motor calibration allows you to skip the calibration phase during setup.

- [SAMD NVM storage driver](src/settings/samd/) - Store settings to the NVM flash memory in your SAMD MCU
- [SAMD NVM storage driver](src/settings/samd/) - Store settings to either the main flash memory or the RWWEE memory (if available) in your SAMD MCU
- [CAT24 I2C EEPROM storage driver](src/settings/i2c/) - Store settings to CAT24 I2C EEPROMs
- [STM32 flash storage driver](src/settings/stm32/) - Store settings directly to STM32 on-board flash, currently supporting STM32G4 MCUs.

Expand All @@ -73,8 +88,11 @@ Drive different kinds of motors, or use alternate algorithms to SimpleFOC's defa

### Utilities

Other support code not fitting in the above categories.

- [STM32 PWM Input driver](src/utilities/stm32pwm/) - PWM Input driver for STM32 MCUs. Accurately measure PWM inputs with zero MCU overhead.
- [STM32 CORDIC trig driver](src/utilities/stm32math/) - CORDIC driver to accellerate sine and cosine calculations in SimpleFOC, on STM32 MCUs which have a CORDIC unit.
- [TrapezoidalPlanner](src/utilities/trapezoids/) - Simple trapezoidal motion planner.

## How to use

Expand Down Expand Up @@ -102,6 +120,13 @@ Find out more information about the Arduino SimpleFOC project on the [docs websi

## Release History

What's changed since 1.0.5?
- Added STSPIN32G4 driver
- Added STM32G4 CORDIC code, for greatly accellerated trig functions on supported MCUs
- Added STM32FlashSettingsStorage driver, supporting STM32G4 MCUs
- Improvements in the MT6835 sensor driver
- Bugfixes [included](https://github.com/simplefoc/Arduino-FOC-drivers/issues?q=is%3Aissue+milestone%3A1.0.6+)

What's changed since 1.0.4?
- Added smoothing sensor by [@dekutree64](https://github.com/dekutree64)
- Added TMD6200 SPI driver by [@YaseenTwati](https://github.com/YaseenTwati)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
#include <Arduino.h>
#include <SPI.h>
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "drivers/simplefocnano/SimpleFOCNanoDriver.h"
#include "encoders/as5048a/MagneticSensorAS5048A.h"


MagneticSensorAS5048A sensor = MagneticSensorAS5048A(PIN_nCS);
SimpleFOCNanoDriver driver = SimpleFOCNanoDriver();
BLDCMotor motor = BLDCMotor(11); // 11 pole pairs

long loopts = 0;
int iterations = 0;
float volts = 0.0f;

void setup() {
Serial.begin(115200); // enable serial port
delay(5000);
SimpleFOCDebug::enable(); // enable debug messages to Serial

sensor.init(); // init sensor on default SPI pins

// read voltage
SimpleFOCDebug::print("Bus voltage: ");
volts = driver.getBusVoltage(5.0f, 1024); // 5V reference, 10-bit ADC
SimpleFOCDebug::println(volts);
driver.voltage_power_supply = volts; // set driver voltage to measured value
driver.voltage_limit = 10.0f; // limit voltage to 10V
driver.pwm_frequency = 30000; // set pwm frequency to 30kHz
driver.init(); // init driver

motor.linkSensor(&sensor); // link the motor to the sensor
motor.linkDriver(&driver); // link the motor to the driver

motor.controller = MotionControlType::torque; // torque control
motor.torque_controller = TorqueControlType::voltage; // use voltage torque control
motor.voltage_limit = driver.voltage_limit / 2.0f; // limit voltage to 1/2 of driver limit
motor.voltage_sensor_align = 4.0f; // align voltage sensor to 4V

motor.init(); // init motor
delay(100); // wait for driver to power up
motor.initFOC(); // init FOC and calibrate motor

Serial.println("Motor ready.");
loopts = millis();

// Set the motor target to 2 volts
motor.target = 2.0f;
}


void loop() {
motor.move();
motor.loopFOC();
long now = millis();
iterations++;
if (now - loopts > 1000) {
Serial.print("Iterations/s: ");
Serial.println(iterations);
Serial.print("Angle: ");
Serial.println(sensor.getAngle());
loopts = now;
iterations = 0;
}
if (now - loopts < 0)
loopts = 0;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
#include <Arduino.h>
#include <SPI.h>
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "drivers/simplefocnano/SimpleFOCNanoDriver.h"
#include "encoders/as5048a/MagneticSensorAS5048A.h"


MagneticSensorAS5048A sensor = MagneticSensorAS5048A(PIN_nCS);
SimpleFOCNanoDriver driver = SimpleFOCNanoDriver();
BLDCMotor motor = BLDCMotor(11); // 11 pole pairs

Commander commander = Commander(Serial);
void doMotor(char* cmd) { commander.motor(&motor, cmd); }

long loopts = 0;
int iterations = 0;
float volts = 0.0f;

void setup() {
Serial.begin(115200); // enable serial port
delay(5000);
SimpleFOCDebug::enable(); // enable debug messages to Serial

sensor.init(); // init sensor on default SPI pins

// read voltage
SimpleFOCDebug::print("Bus voltage: ");
volts = driver.getBusVoltage(3.3, 4096);
SimpleFOCDebug::println(volts);
driver.voltage_power_supply = volts; // set driver voltage to measured value
driver.voltage_limit = 10.0f; // limit voltage to 10V
driver.pwm_frequency = 30000; // set pwm frequency to 30kHz
driver.init(); // init driver

motor.linkSensor(&sensor); // link the motor to the sensor
motor.linkDriver(&driver); // link the motor to the driver

motor.controller = MotionControlType::torque; // torque control
motor.torque_controller = TorqueControlType::voltage; // use voltage torque control
motor.voltage_limit = driver.voltage_limit / 2.0f; // limit voltage to 1/2 of driver limit
motor.voltage_sensor_align = 4.0f; // align voltage sensor to 4V

motor.init(); // init motor
delay(100); // wait for driver to power up
motor.initFOC(); // init FOC and calibrate motor

commander.add('M', doMotor); // add motor command

Serial.println("Motor ready.");
loopts = millis();
}


void loop() {
motor.move();
motor.loopFOC();
commander.run();
long now = millis();
iterations++;
if (now - loopts > 1000) {
Serial.print("Iterations/s: ");
Serial.println(iterations);
Serial.print("Angle: ");
Serial.println(sensor.getAngle());
loopts = now;
iterations = 0;
}
if (now - loopts < 0)
loopts = 0;
}
Loading

0 comments on commit bfd07bd

Please sign in to comment.