Skip to content

Commit 1520b63

Browse files
Merge pull request #485 from silabs-szabog/feat_support_efr32
Add Silabs drivers and examples
2 parents 0c86169 + 7cfd709 commit 1520b63

File tree

15 files changed

+2170
-1
lines changed

15 files changed

+2170
-1
lines changed

.github/workflows/arduino.yml

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,15 @@ jobs:
2525
- arduino-boards-fqbn: arduino:avr:uno # arudino uno - compiling almost all examples
2626
sketch-names: '**.ino'
2727
required-libraries: PciManager
28-
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
28+
sketches-exclude: align_current_sense, measure_inductance_and_resistance,
29+
teensy4_current_control_low_side, full_control_serial, angle_control,
30+
bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example,
31+
stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm,
32+
osc_esp32_fullcontrol, nano33IoT_velocity_control, smartstepper_control,
33+
esp32_current_control_low_side, stm32_spi_alt_example, esp32_spi_alt_example,
34+
B_G431B_ESC1, odrive_example_spi, odrive_example_encoder, single_full_control_example,
35+
double_full_control_example, stm32_current_control_low_side, open_loop_velocity_6pwm,
36+
efr32_hall_sensor_velocity_6pwm, efr32_open_loop_velocity_6pwm, efr32_torque_velocity_6pwm
2937

3038
- arduino-boards-fqbn: arduino:sam:arduino_due_x # arduino due - one full example
3139
sketch-names: single_full_control_example.ino

.github/workflows/silabs.yml

Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
name: SILABS
2+
on: [push, pull_request]
3+
jobs:
4+
lint:
5+
runs-on: ubuntu-latest
6+
steps:
7+
- uses: actions/checkout@v2
8+
- uses: arduino/arduino-lint-action@v1
9+
with:
10+
library-manager: update
11+
project-type: library
12+
build:
13+
name: Test compiling
14+
runs-on: ubuntu-latest
15+
16+
strategy:
17+
matrix:
18+
arduino-boards-fqbn:
19+
- SiliconLabs:silabs:nano_matter # efr32 nano matter
20+
21+
include:
22+
23+
- arduino-boards-fqbn: SiliconLabs:silabs:nano_matter
24+
platform-url: https://siliconlabs.github.io/arduino/package_arduinosilabs_index.json
25+
sketch-names: efr32_hall_sensor_velocity_6pwm.ino, efr32_open_loop_velocity_6pwm.ino, efr32_torque_velocity_6pwm.ino
26+
27+
# Do not cancel all jobs / architectures if one job fails
28+
fail-fast: false
29+
steps:
30+
- name: Checkout
31+
uses: actions/checkout@master
32+
- name: Compile all examples
33+
uses: ArminJo/arduino-test-compile@master
34+
with:
35+
arduino-board-fqbn: ${{ matrix.arduino-boards-fqbn }}
36+
required-libraries: ${{ matrix.required-libraries }}
37+
platform-url: ${{ matrix.platform-url }}
38+
sketch-names: ${{ matrix.sketch-names }}
39+
sketches-exclude: ${{ matrix.sketches-exclude }}
40+
build-properties: ${{ toJson(matrix.build-properties) }}
41+
Lines changed: 168 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,168 @@
1+
/**
2+
* Silabs MG24 6PWM closed loop velocity control example with HALL sensor based rotor position
3+
*
4+
* HARDWARE CONFIGURATION:
5+
* CPU Board: Arduino Nano Matter
6+
* Motor Driver Board: BOOSTXL-DRV8305EVM
7+
* BLDC Motor: Newark DF45M024053-A2
8+
*/
9+
10+
#include <SimpleFOC.h>
11+
12+
#define HALL_SENSOR_IRQ 1
13+
#define ENABLE_MONITOR 0
14+
15+
static bool allow_run = false;
16+
17+
// BLDC motor instance
18+
BLDCMotor *motor;
19+
20+
// BLDC driver instance
21+
BLDCDriver6PWM *driver;
22+
23+
// Commander instance
24+
Commander *command;
25+
26+
// Hall sensor instance
27+
HallSensor *sensor;
28+
29+
// Interrupt routine initialization
30+
// channel A and B callbacks
31+
void doA() { sensor->handleA(); }
32+
void doB() { sensor->handleB(); }
33+
void doC() { sensor->handleC(); }
34+
35+
void doMotor(char* cmd) {
36+
if (!command) return;
37+
command->motor(motor, cmd);
38+
}
39+
40+
void setup() {
41+
// use monitoring with serial
42+
Serial.begin(115200);
43+
// enable more verbose output for debugging
44+
// comment out if not needed
45+
SimpleFOCDebug::enable(&Serial);
46+
47+
// Commander
48+
command = new Commander(Serial);
49+
if (!command) return;
50+
51+
// Driver
52+
driver = new BLDCDriver6PWM(6, 7, 8, 9, 10, 11, 12);
53+
if (!driver) return;
54+
55+
// Driver config
56+
// power supply voltage [V]
57+
driver->voltage_power_supply = 24;
58+
// pwm frequency to be used [Hz]
59+
driver->pwm_frequency = 20000; // 20 kHz
60+
// Max DC voltage allowed - default voltage_power_supply
61+
driver->voltage_limit = 12;
62+
// dead zone percentage of the duty cycle - default 0.02 - 2%
63+
// Can set value to 0 because the DRV8305 will provide the
64+
// required dead-time.
65+
driver->dead_zone = 0;
66+
67+
// init driver
68+
if (!driver->init()) {
69+
Serial.println("Driver init failed!");
70+
return;
71+
}
72+
driver->enable();
73+
74+
// HallSensor(int encA, int encB, int encC, int pp)
75+
// - encA, encB, encC - HallSensor A, B and C pins
76+
// - pp - pole pairs
77+
sensor = new HallSensor(5, 4, 13, 8);
78+
if (!sensor) return;
79+
80+
// initialize sensor sensor hardware
81+
sensor->init();
82+
83+
#if HALL_SENSOR_IRQ
84+
sensor->enableInterrupts(doA, doB, doC);
85+
#else
86+
// Note: There is a bug when initializing HallSensor in heap, attribute
87+
// `use_interrupt` gets value not `false` even `enableInterrupts` has not been
88+
// called. So we initialize this attribute value `false` after creating a
89+
// `HallSensor` instance.
90+
sensor->use_interrupt = false;
91+
#endif
92+
93+
// Motor
94+
motor = new BLDCMotor(8);
95+
if (!motor) return;
96+
97+
// link the motor and the driver
98+
motor->linkDriver(driver);
99+
100+
// link the motor to the sensor
101+
motor->linkSensor(sensor);
102+
103+
// Set below the motor's max 5600 RPM limit = 586 rad/s
104+
motor->velocity_limit = 530.0f;
105+
106+
// set motion control loop to be used
107+
motor->controller = MotionControlType::velocity;
108+
109+
// choose FOC modulation (optional) - SinePWM or SpaceVectorPWM
110+
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
111+
112+
// controller configuration
113+
// velocity PI controller parameters
114+
motor->PID_velocity.P = 0.05f;
115+
motor->PID_velocity.I = 1;
116+
117+
// velocity low pass filtering time constant
118+
motor->LPF_velocity.Tf = 0.01f;
119+
120+
#if ENABLE_MONITOR
121+
motor->useMonitoring(Serial);
122+
motor->monitor_variables = _MON_TARGET | _MON_VEL;
123+
#endif
124+
125+
// initialize motor
126+
if (!motor->init()) {
127+
Serial.println("Motor init failed!");
128+
return;
129+
}
130+
131+
// align sensor and start FOC
132+
if (!motor->initFOC()) {
133+
Serial.println("FOC init failed!");
134+
return;
135+
}
136+
137+
// add target command M
138+
command->add('M', doMotor, "motor");
139+
140+
Serial.println("Motor ready!");
141+
Serial.println("Set target velocity [rad/s]");
142+
143+
allow_run = true;
144+
_delay(1000);
145+
}
146+
147+
void loop() {
148+
if (!allow_run) return;
149+
150+
// main FOC algorithm function
151+
// the faster you run this function the better
152+
motor->loopFOC();
153+
154+
// Motion control function
155+
// velocity, position or voltage (defined in motor.controller)
156+
// this function can be run at much lower frequency than loopFOC() function
157+
// You can also use motor.move() and set the motor.target in the code
158+
motor->move();
159+
160+
#if ENABLE_MONITOR
161+
// function intended to be used with serial plotter to monitor motor variables
162+
// significantly slowing the execution down!!!!
163+
motor->monitor();
164+
#endif
165+
166+
// user communication
167+
command->run();
168+
}
Lines changed: 104 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,104 @@
1+
/**
2+
* Silabs MG24 6PWM open loop velocity control example
3+
*
4+
* HARDWARE CONFIGURATION:
5+
* CPU Board: Arduino Nano Matter
6+
* Motor Driver Board: BOOSTXL-DRV8305EVM
7+
* BLDC Motor: Newark DF45M024053-A2
8+
*/
9+
10+
#include <SimpleFOC.h>
11+
12+
static bool allow_run = false;
13+
14+
// BLDC motor instance
15+
BLDCMotor *motor;
16+
17+
// BLDC driver instance
18+
BLDCDriver6PWM *driver;
19+
20+
// Commander instance
21+
Commander *command;
22+
23+
void doMotor(char* cmd) {
24+
if (!command) return;
25+
command->motor(motor, cmd);
26+
}
27+
28+
void setup() {
29+
// use monitoring with serial
30+
Serial.begin(115200);
31+
// enable more verbose output for debugging
32+
// comment out if not needed
33+
SimpleFOCDebug::enable(&Serial);
34+
35+
// Commander
36+
command = new Commander(Serial);
37+
if (!command) return;
38+
39+
// Driver
40+
driver = new BLDCDriver6PWM(6, 7, 8, 9, 10, 11, 12);
41+
if (!driver) return;
42+
43+
// Driver config
44+
// power supply voltage [V]
45+
driver->voltage_power_supply = 24;
46+
// pwm frequency to be used [Hz]
47+
driver->pwm_frequency = 20000; // 20 kHz
48+
// Max DC voltage allowed - default voltage_power_supply
49+
driver->voltage_limit = 12;
50+
// dead zone percentage of the duty cycle - default 0.02 - 2%
51+
// Can set value to 0 because the DRV8305 will provide the
52+
// required dead-time.
53+
driver->dead_zone = 0;
54+
55+
// init driver
56+
if (!driver->init()) {
57+
Serial.println("Driver init failed!");
58+
return;
59+
}
60+
driver->enable();
61+
62+
// Motor
63+
motor = new BLDCMotor(8);
64+
if (!motor) return;
65+
66+
// link the motor and the driver
67+
motor->linkDriver(driver);
68+
69+
// default voltage_power_supply
70+
motor->voltage_limit = 0.8f;
71+
72+
// set motion control loop to be used
73+
motor->controller = MotionControlType::velocity_openloop;
74+
75+
// choose FOC modulation (optional) - SinePWM or SpaceVectorPWM
76+
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
77+
78+
// initialize motor
79+
if (!motor->init()) {
80+
Serial.println("Motor init failed!");
81+
return;
82+
}
83+
84+
// add target command M
85+
command->add('M', doMotor, "motor");
86+
87+
Serial.println("Motor ready!");
88+
Serial.println("Set target velocity [rad/s]");
89+
90+
allow_run = true;
91+
_delay(1000);
92+
}
93+
94+
95+
void loop() {
96+
if (!allow_run) return;
97+
98+
// open loop velocity movement
99+
// using motor.voltage_limit
100+
motor->move();
101+
102+
// user communication
103+
command->run();
104+
}

0 commit comments

Comments
 (0)