Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 9 additions & 1 deletion .github/workflows/arduino.yml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,15 @@ jobs:
- arduino-boards-fqbn: arduino:avr:uno # arudino uno - compiling almost all examples
sketch-names: '**.ino'
required-libraries: PciManager
sketches-exclude: align_current_sense, measure_inductance_and_resistance, teensy4_current_control_low_side, full_control_serial, angle_control, bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm, osc_esp32_fullcontrol, nano33IoT_velocity_control, smartstepper_control,esp32_current_control_low_side, stm32_spi_alt_example, esp32_spi_alt_example, B_G431B_ESC1, odrive_example_spi, odrive_example_encoder, single_full_control_example, double_full_control_example, stm32_current_control_low_side, open_loop_velocity_6pwm
sketches-exclude: align_current_sense, measure_inductance_and_resistance,
teensy4_current_control_low_side, full_control_serial, angle_control,
bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example,
stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm,
osc_esp32_fullcontrol, nano33IoT_velocity_control, smartstepper_control,
esp32_current_control_low_side, stm32_spi_alt_example, esp32_spi_alt_example,
B_G431B_ESC1, odrive_example_spi, odrive_example_encoder, single_full_control_example,
double_full_control_example, stm32_current_control_low_side, open_loop_velocity_6pwm,
efr32_hall_sensor_velocity_6pwm, efr32_open_loop_velocity_6pwm, efr32_torque_velocity_6pwm

- arduino-boards-fqbn: arduino:sam:arduino_due_x # arduino due - one full example
sketch-names: single_full_control_example.ino
Expand Down
41 changes: 41 additions & 0 deletions .github/workflows/silabs.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
name: SILABS
on: [push, pull_request]
jobs:
lint:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- uses: arduino/arduino-lint-action@v1
with:
library-manager: update
project-type: library
build:
name: Test compiling
runs-on: ubuntu-latest

strategy:
matrix:
arduino-boards-fqbn:
- SiliconLabs:silabs:nano_matter # efr32 nano matter

include:

- arduino-boards-fqbn: SiliconLabs:silabs:nano_matter
platform-url: https://siliconlabs.github.io/arduino/package_arduinosilabs_index.json
sketch-names: efr32_hall_sensor_velocity_6pwm.ino, efr32_open_loop_velocity_6pwm.ino, efr32_torque_velocity_6pwm.ino

# Do not cancel all jobs / architectures if one job fails
fail-fast: false
steps:
- name: Checkout
uses: actions/checkout@master
- name: Compile all examples
uses: ArminJo/arduino-test-compile@master
with:
arduino-board-fqbn: ${{ matrix.arduino-boards-fqbn }}
required-libraries: ${{ matrix.required-libraries }}
platform-url: ${{ matrix.platform-url }}
sketch-names: ${{ matrix.sketch-names }}
sketches-exclude: ${{ matrix.sketches-exclude }}
build-properties: ${{ toJson(matrix.build-properties) }}

Original file line number Diff line number Diff line change
@@ -0,0 +1,168 @@
/**
* Silabs MG24 6PWM closed loop velocity control example with HALL sensor based rotor position
*
* HARDWARE CONFIGURATION:
* CPU Board: Arduino Nano Matter
* Motor Driver Board: BOOSTXL-DRV8305EVM
* BLDC Motor: Newark DF45M024053-A2
*/

#include <SimpleFOC.h>

#define HALL_SENSOR_IRQ 1
#define ENABLE_MONITOR 0

static bool allow_run = false;

// BLDC motor instance
BLDCMotor *motor;

// BLDC driver instance
BLDCDriver6PWM *driver;

// Commander instance
Commander *command;

// Hall sensor instance
HallSensor *sensor;

// Interrupt routine initialization
// channel A and B callbacks
void doA() { sensor->handleA(); }
void doB() { sensor->handleB(); }
void doC() { sensor->handleC(); }

void doMotor(char* cmd) {
if (!command) return;
command->motor(motor, cmd);
}

void setup() {
// use monitoring with serial
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);

// Commander
command = new Commander(Serial);
if (!command) return;

// Driver
driver = new BLDCDriver6PWM(6, 7, 8, 9, 10, 11, 12);
if (!driver) return;

// Driver config
// power supply voltage [V]
driver->voltage_power_supply = 24;
// pwm frequency to be used [Hz]
driver->pwm_frequency = 20000; // 20 kHz
// Max DC voltage allowed - default voltage_power_supply
driver->voltage_limit = 12;
// dead zone percentage of the duty cycle - default 0.02 - 2%
// Can set value to 0 because the DRV8305 will provide the
// required dead-time.
driver->dead_zone = 0;

// init driver
if (!driver->init()) {
Serial.println("Driver init failed!");
return;
}
driver->enable();

// HallSensor(int encA, int encB, int encC, int pp)
// - encA, encB, encC - HallSensor A, B and C pins
// - pp - pole pairs
sensor = new HallSensor(5, 4, 13, 8);
if (!sensor) return;

// initialize sensor sensor hardware
sensor->init();

#if HALL_SENSOR_IRQ
sensor->enableInterrupts(doA, doB, doC);
#else
// Note: There is a bug when initializing HallSensor in heap, attribute
// `use_interrupt` gets value not `false` even `enableInterrupts` has not been
// called. So we initialize this attribute value `false` after creating a
// `HallSensor` instance.
sensor->use_interrupt = false;
#endif

// Motor
motor = new BLDCMotor(8);
if (!motor) return;

// link the motor and the driver
motor->linkDriver(driver);

// link the motor to the sensor
motor->linkSensor(sensor);

// Set below the motor's max 5600 RPM limit = 586 rad/s
motor->velocity_limit = 530.0f;

// set motion control loop to be used
motor->controller = MotionControlType::velocity;

// choose FOC modulation (optional) - SinePWM or SpaceVectorPWM
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;

// controller configuration
// velocity PI controller parameters
motor->PID_velocity.P = 0.05f;
motor->PID_velocity.I = 1;

// velocity low pass filtering time constant
motor->LPF_velocity.Tf = 0.01f;

#if ENABLE_MONITOR
motor->useMonitoring(Serial);
motor->monitor_variables = _MON_TARGET | _MON_VEL;
#endif

// initialize motor
if (!motor->init()) {
Serial.println("Motor init failed!");
return;
}

// align sensor and start FOC
if (!motor->initFOC()) {
Serial.println("FOC init failed!");
return;
}

// add target command M
command->add('M', doMotor, "motor");

Serial.println("Motor ready!");
Serial.println("Set target velocity [rad/s]");

allow_run = true;
_delay(1000);
}

void loop() {
if (!allow_run) return;

// main FOC algorithm function
// the faster you run this function the better
motor->loopFOC();

// Motion control function
// velocity, position or voltage (defined in motor.controller)
// this function can be run at much lower frequency than loopFOC() function
// You can also use motor.move() and set the motor.target in the code
motor->move();

#if ENABLE_MONITOR
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
motor->monitor();
#endif

// user communication
command->run();
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
/**
* Silabs MG24 6PWM open loop velocity control example
*
* HARDWARE CONFIGURATION:
* CPU Board: Arduino Nano Matter
* Motor Driver Board: BOOSTXL-DRV8305EVM
* BLDC Motor: Newark DF45M024053-A2
*/

#include <SimpleFOC.h>

static bool allow_run = false;

// BLDC motor instance
BLDCMotor *motor;

// BLDC driver instance
BLDCDriver6PWM *driver;

// Commander instance
Commander *command;

void doMotor(char* cmd) {
if (!command) return;
command->motor(motor, cmd);
}

void setup() {
// use monitoring with serial
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);

// Commander
command = new Commander(Serial);
if (!command) return;

// Driver
driver = new BLDCDriver6PWM(6, 7, 8, 9, 10, 11, 12);
if (!driver) return;

// Driver config
// power supply voltage [V]
driver->voltage_power_supply = 24;
// pwm frequency to be used [Hz]
driver->pwm_frequency = 20000; // 20 kHz
// Max DC voltage allowed - default voltage_power_supply
driver->voltage_limit = 12;
// dead zone percentage of the duty cycle - default 0.02 - 2%
// Can set value to 0 because the DRV8305 will provide the
// required dead-time.
driver->dead_zone = 0;

// init driver
if (!driver->init()) {
Serial.println("Driver init failed!");
return;
}
driver->enable();

// Motor
motor = new BLDCMotor(8);
if (!motor) return;

// link the motor and the driver
motor->linkDriver(driver);

// default voltage_power_supply
motor->voltage_limit = 0.8f;

// set motion control loop to be used
motor->controller = MotionControlType::velocity_openloop;

// choose FOC modulation (optional) - SinePWM or SpaceVectorPWM
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;

// initialize motor
if (!motor->init()) {
Serial.println("Motor init failed!");
return;
}

// add target command M
command->add('M', doMotor, "motor");

Serial.println("Motor ready!");
Serial.println("Set target velocity [rad/s]");

allow_run = true;
_delay(1000);
}


void loop() {
if (!allow_run) return;

// open loop velocity movement
// using motor.voltage_limit
motor->move();

// user communication
command->run();
}
Loading