diff --git a/.github/workflows/arduino.yml b/.github/workflows/arduino.yml index 5f2009be..37d12ab6 100644 --- a/.github/workflows/arduino.yml +++ b/.github/workflows/arduino.yml @@ -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 diff --git a/.github/workflows/silabs.yml b/.github/workflows/silabs.yml new file mode 100644 index 00000000..7d78b5bd --- /dev/null +++ b/.github/workflows/silabs.yml @@ -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) }} + diff --git a/examples/hardware_specific_examples/Silabs/efr32_hall_sensor_velocity_6pwm/efr32_hall_sensor_velocity_6pwm.ino b/examples/hardware_specific_examples/Silabs/efr32_hall_sensor_velocity_6pwm/efr32_hall_sensor_velocity_6pwm.ino new file mode 100644 index 00000000..8ca6bfa2 --- /dev/null +++ b/examples/hardware_specific_examples/Silabs/efr32_hall_sensor_velocity_6pwm/efr32_hall_sensor_velocity_6pwm.ino @@ -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 + +#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(); +} diff --git a/examples/hardware_specific_examples/Silabs/efr32_open_loop_velocity_6pwm/efr32_open_loop_velocity_6pwm.ino b/examples/hardware_specific_examples/Silabs/efr32_open_loop_velocity_6pwm/efr32_open_loop_velocity_6pwm.ino new file mode 100644 index 00000000..0dcd02be --- /dev/null +++ b/examples/hardware_specific_examples/Silabs/efr32_open_loop_velocity_6pwm/efr32_open_loop_velocity_6pwm.ino @@ -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 + +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(); +} diff --git a/examples/hardware_specific_examples/Silabs/efr32_torque_velocity_6pwm/efr32_torque_velocity_6pwm.ino b/examples/hardware_specific_examples/Silabs/efr32_torque_velocity_6pwm/efr32_torque_velocity_6pwm.ino new file mode 100644 index 00000000..4f1218cc --- /dev/null +++ b/examples/hardware_specific_examples/Silabs/efr32_torque_velocity_6pwm/efr32_torque_velocity_6pwm.ino @@ -0,0 +1,205 @@ +/** + * Silabs MG24 6PWM closed loop velocity and torque 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 + +#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; + +// Current sensor +LowsideCurrentSense *current_sense; + +// 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 torque mode + motor->torque_controller = TorqueControlType::foc_current; + + // 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.025f; + motor->PID_velocity.I = 0.4f; + + // velocity low pass filtering time constant + motor->LPF_velocity.Tf = 0.01f; + + // current q loop PID + motor->PID_current_q.P = 1.0f; + motor->PID_current_q.I = 100.0f; + motor->LPF_current_q.Tf = 0.01f; + + // current d loop PID + motor->PID_current_d.P = 1.0f; + motor->PID_current_d.I = 100.0f; + motor->LPF_current_d.Tf = 0.01f; + +#if ENABLE_MONITOR + // comment out if not needed + motor->useMonitoring(Serial); + motor->monitor_variables = _MON_TARGET | _MON_CURR_Q | _MON_CURR_D | _MON_VEL; +#endif + + // initialize motor + if (!motor->init()) { + Serial.println("Motor init failed!"); + return; + } + + // Current Sense + current_sense = new LowsideCurrentSense(0.007f, 10.0f, A0, A1, A2); + if (!current_sense) return; + + // link current sense and the driver + current_sense->linkDriver(driver); + + if (!current_sense->init()) { + Serial.println("Current Sense init failed!"); + return; + } + + // DRV8305 has inverted gains on all channels + current_sense->gain_a *= -1; + current_sense->gain_b *= -1; + current_sense->gain_c *= -1; + + // link the motor and the driver + motor->linkCurrentSense(current_sense); + + // 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(); +} diff --git a/examples/hardware_specific_examples/Silabs/hw_setup.png b/examples/hardware_specific_examples/Silabs/hw_setup.png new file mode 100644 index 00000000..56a3af6f Binary files /dev/null and b/examples/hardware_specific_examples/Silabs/hw_setup.png differ diff --git a/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.drawio b/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.drawio new file mode 100644 index 00000000..3b993400 --- /dev/null +++ b/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.drawio @@ -0,0 +1,177 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.png b/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.png new file mode 100644 index 00000000..0c11c2d4 Binary files /dev/null and b/examples/hardware_specific_examples/Silabs/nanoMatterMC_Wiring.png differ diff --git a/examples/hardware_specific_examples/Silabs/readme.md b/examples/hardware_specific_examples/Silabs/readme.md new file mode 100644 index 00000000..2837dcfe --- /dev/null +++ b/examples/hardware_specific_examples/Silabs/readme.md @@ -0,0 +1,144 @@ +# Silabs Hardware-Specific Examples for SimpleFOC + +This folder contains **hardware-specific example projects** for running the [SimpleFOC](https://docs.simplefoc.com/) library on **Silicon Labs EFR32 microcontrollers** (tested on Arduino Nano Matter). Each example demonstrates a motor control use case using a **6PWM BLDC driver**. + +**Example List** + +- **efr32_hall_sensor_velocity_6pwm** + - Demonstrates velocity control of a BLDC motor using a Hall sensor for feedback and a 6PWM driver on an EFR32 board. + +- **efr32_open_loop_velocity_6pwm** + - Shows how to run a BLDC motor in open-loop velocity mode (no sensor feedback) using a 6PWM driver on EFR32. + +- **efr32_torque_velocity_6pwm** + - Example of torque and velocity control for a BLDC motor using a 6PWM driver on EFR32, suitable for advanced control scenarios. + +## Hardware Setup + +Required hardware: + +* **Arduino Nano Matter (EFR32MG24)** [https://docs.arduino.cc/hardware/nano-matter/](https://docs.arduino.cc/hardware/nano-matter/) +* **DRV8305 BoosterPack (BOOSTXL-DRV8305EVM)** +* **BLDC Motor: DF45M024053 – A2** +* USB cable for programming and serial monitor + +A dedicated interface board set-up connecting the Motor - Power Stage - Nano Matter. Jump wires can be used as well to connect the boards. + +![hw_setup](hw_setup.png) + +Connect the Arduino Nano Matter board to the DRV8305EVM according to the board pin mapping (phase outputs, PWM inputs, and Hall sensor connections). + +![MC Wiring](nanoMatterMC_Wiring.png) + +### Wiring Table: Arduino Nano Matter to BOOSTXL-DRV8305 & BLDC Motor + +This table describes the connections between the Arduino Nano Matter, the TI BOOSTXL-DRV8305 driver board, and a 3-phase BLDC motor with Hall sensors. + +| From (Nano Matter Pin) | To (DRV8305 BoosterPack Pin) | BLDC MOTOR | Function / Description | +| :--- | :--- | :--- | :---| +| `3.3V` | `3V3` | HALL/ENC Supply* | 3.3V Power the BoosterPack provides 3.3V through an LDO | +| `GND` | `PowerSupply GND` | HALL/ENC sensor GND | Common Ground | +| N/A | `PowerSupply 12V` | N/A | Power supply for power stage 4.4 to 45 V, consider motor power| +| `A0` | `ISENA` | N/A | Phase A current sense | +| `A1` | `ISENB` | N/A | Phase B current sense | +| `A2` | `ISENC` | N/A | Phase C current sense | +| `A3` | `VSENA` | N/A | Phase A Voltage sense (Optional, not mandatory to run examples) | +| `A4` | `VSENB` | N/A | Phase B Voltage sense (Optional, not mandatory to run examples) | +| `A5` | `VSENC` | N/A | Phase C Voltage sense (Optional, not mandatory to run examples)| +| `A6` | `VSENVPVDD` | N/A | DC BUS Voltage sense (Optional, not mandatory to run examples)| +| `D0` (MOSI1) | `SDI` | N/A | DRV8035 SPI connection, configuration and status reading (Optional, not mandatory to run examples)| +| `D1` (MISO1) | `SDO` | N/A | DRV8035 SPI connection, configuration and status reading (Optional, not mandatory to run examples)| +| `D2` (SCK1) | `SCLK`| N/A | DRV8035 SPI clock, configuration and status reading (Optional, not mandatory to run examples)| +| `D3` (SS1) | `SCS` | N/A | DRV8035 SPI chip select, configuration and status reading (Optional, not mandatory to run examples)| +| `D4` | N/A | HALL A or Encoder A | Motor sensor connection (Hall configuration in examples) | +| `D5` | N/A | HALL B or Encoder B | Motor sensor connection (Hall configuration in examples) | +| `D6` | `PWMHA` | N/A | PWM Phase A High-Side Gate Signal | +| `D7` | `PWMLA` | N/A | PWM Phase A Low-Side Gate Signal | +| `D8` | `PWMHB` | N/A | PWM Phase B High-Side Gate Signal | +| `D9` | `PWMLB` | N/A | PWM Phase B Low-Side Gate Signal | +| `D10` | `PWMHC` | N/A | PWM Phase C High-Side Gate Signal | +| `D11` | `PWMLC` | N/A | PWM Phase C Low-Side Gate Signal | +| `D12` | `ENGATE` | N/A | Enable DRV8305 gate driver | +| `D13` | N/A | HALL C or Encoder Index | Motor sensor connection (Hall configuration in examples) | +| N/A | `PHASE U` | `PHASE U` | Motor phase connection | +| N/A | `PHASE V` | `PHASE V` | Motor phase connection | +| N/A | `PHASE W` | `PHASE W` | Motor phase connection | + +**Important Notes:** +* **Power:** Ensure the DRV8305's `PVDD` and `GVDD` jumpers are correctly set for your motor's voltage. The power supply should be rated at least twice the motor’s nominal power. The BoosterPack can supply the Nano Matter if it is not connected to USB. +* **Rotor sensor:** Some Encoder or Hall sensors might require 5V supply, make sure of proper level shifting if required. +* **SPI:** The SPI connection (`nSCS`, `SPI_CLK`, `SPI_MOSI`, `SPI_MISO`) is used to configure the DRV8305 driver IC (e.g., set gain, fault parameters). It is optional for the examples. The examples are using the default gate driver configuration. Only needed if you wish to change the default gate driver configuration (e.g., dead time, fault parameters). + +--- + +## Software Setup + +1. **Arduino IDE** + + * Use Arduino IDE **2.3.4 or later**. + * [Download here](https://www.arduino.cc/en/software). + +2. **Silicon Labs Arduino Core** + + * Open *Boards Manager* in Arduino IDE. + * Search for *Silicon Labs* and install the latest version (**2.3.0** or newer). + * If not found, add this URL under *Preferences → Additional Boards Manager URLs*: + + ``` + https://siliconlabs.github.io/arduino/package_arduinosilabs_index.json + ``` + +3. **SimpleFOC (Silabs-modified version)** + + * Open *Library Manager* in Arduino IDE. + * Search and add *Simple FOC* library + +4. **(Optional) SimpleFOC Studio or web viewer** + + * For runtime tuning and monitoring. + * [Docs](https://docs.simplefoc.com/studio) + * [Enable Monitoring](https://docs.simplefoc.com/monitoring) + +--- + +## Running the Examples + +1. Open the `.ino` file in Arduino IDE. +2. Select your **Arduino Nano Matter** board. +3. Compile & upload. +4. Open the Serial Monitor (115200 baud) +5. (Optional) Connect with monitoring tools. + 1. Modification of the example code is necessary to enable monitoring feature. + 2. [Enable Monitoring](https://docs.simplefoc.com/monitoring) + +### Example Commands + +Send commands to control the motor: + +``` bash +M50 # Run clockwise at 50 rad/s +M-50 # Run counter-clockwise at 50 rad/s +M0 # Stop motor +``` + +--- + +## Notes on EFR32 Porting + +The EFR32 port of SimpleFOC includes: + +* Full **6PWM driver support** (deadtime insertion, duty cycle updates). +* **Current sense integration** (low-side sensing tested). +* **Arduino-style pin mapping** for portability. + +--- + +## References + +* [SimpleFOC Documentation](https://docs.simplefoc.com/) +* [Commander Interface](https://docs.simplefoc.com/commander_interface) +* [Arduino Nano Matter Manual](https://docs.arduino.cc/tutorials/nano-matter/user-manual/) +* [Silicon Labs Arduino Core](https://github.com/SiliconLabs/arduino) +* [SimpleFOC Studio](https://github.com/JorgeMaker/SimpleFOCStudio) + + diff --git a/src/current_sense/hardware_specific/silabs/efr32_mcu.cpp b/src/current_sense/hardware_specific/silabs/efr32_mcu.cpp new file mode 100644 index 00000000..6ebbbf2e --- /dev/null +++ b/src/current_sense/hardware_specific/silabs/efr32_mcu.cpp @@ -0,0 +1,426 @@ +#if defined(ARDUINO_ARCH_SILABS) +#include +#include + +#include +#include +#include "efr32_mcu.h" +#include "../../../drivers/hardware_specific/silabs/efr32_mcu.h" + +#ifndef _ADC_VOLTAGE +#define _ADC_VOLTAGE 3.3f +#endif + +#ifndef _ADC_RESOLUTION +#define _ADC_RESOLUTION 4095.0f +#endif + +#ifndef _CLK_SRC_ADC_FREQ +#define _CLK_SRC_ADC_FREQ 20000000 +#endif + +#ifndef _CLK_ADC_FREQ +#define _CLK_ADC_FREQ 10000000 +#endif + +extern void _getPrsSourceAndUnderflowSignal( + TIMER_TypeDef *timer, + uint32_t *source, + uint32_t *signal); + +static void _adcBusAllocate( + uint8_t port, + uint8_t pin +) { + switch (port) { +#if (GPIO_PA_COUNT > 0) + case gpioPortA: + if (0 == pin % 2) { + if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AEVEN0_MASK) == GPIO_ABUSALLOC_AEVEN0_TRISTATE) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN0_ADC0; + } else if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AEVEN1_MASK) == GPIO_ABUSALLOC_AEVEN1_TRISTATE) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN1_ADC0; + } else {} + } else { + if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AODD0_MASK) == GPIO_ABUSALLOC_AODD0_TRISTATE) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD0_ADC0; + } else if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AODD1_MASK) == GPIO_ABUSALLOC_AODD1_TRISTATE) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD1_ADC0; + } else { + // MISRA + } + } + break; +#endif + +#if (GPIO_PB_COUNT > 0) + case gpioPortB: + if (0 == pin % 2) { + if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BEVEN0_MASK) == GPIO_BBUSALLOC_BEVEN0_TRISTATE) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN0_ADC0; + } else if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BEVEN1_MASK) == GPIO_BBUSALLOC_BEVEN1_TRISTATE) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN1_ADC0; + } else { + // MISRA + } + } else { + if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BODD0_MASK) == GPIO_BBUSALLOC_BODD0_TRISTATE) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD0_ADC0; + } else if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BODD1_MASK) == GPIO_BBUSALLOC_BODD1_TRISTATE) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD1_ADC0; + } else { + // MISRA + } + } + break; +#endif + +#if (GPIO_PC_COUNT > 0 || GPIO_PD_COUNT > 0) + case gpioPortC: + case gpioPortD: + if (0 == pin % 2) { + if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDEVEN0_MASK) == GPIO_CDBUSALLOC_CDEVEN0_TRISTATE) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN0_ADC0; + } else if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDEVEN1_MASK) == GPIO_CDBUSALLOC_CDEVEN1_TRISTATE) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN1_ADC0; + } else { + // MISRA + } + } else { + if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDODD0_MASK) == GPIO_CDBUSALLOC_CDODD0_TRISTATE) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD0_ADC0; + } else if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDODD1_MASK) == GPIO_CDBUSALLOC_CDODD1_TRISTATE) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD1_ADC0; + } else { + // MISRA + } + } + break; +#endif + } +} + +static void _adcConfig( + EFR32AdcInstance *inst, + const int pin +) { + if (!inst) return; + inst->port = getSilabsPortFromArduinoPin(pinToPinName(pin)); + inst->pin = getSilabsPinFromArduinoPin(pinToPinName(pin)); +} + +static float _readAdc( + EFR32CurrentSenseParams *params, + const int pin +) { + if (!params) return 0.0f; + + for (uint8_t i = 0; i < SILABS_MAX_ANALOG; ++i) { + if (!_isset(params->pins[i])) continue; + if (pin == params->pins[i]) { + return params->buffer[i] * params->adc_voltage_conv; + } + } + return 0.0f; +} + +static bool _dmaTransferFinishedCb( + unsigned int channel, + unsigned int sequenceNo, + void *data +) { + _UNUSED(sequenceNo); + + EFR32CurrentSenseParams *params = (EFR32CurrentSenseParams *) data; + if (!params || !params->adc || (params->dmaChannel != channel)) + return false; + + CORE_DECLARE_IRQ_STATE; + CORE_ENTER_ATOMIC(); + params->dataReady = true; + CORE_EXIT_ATOMIC(); + + return false; +} + +static void _currentSenseInitDMA( + EFR32CurrentSenseParams *params, + DMADRV_Callback_t fn, + void *data +) { + if (!params) return; + + // Initialize DMA with default parameters + DMADRV_Init(); + + DMADRV_AllocateChannel(¶ms->dmaChannel, NULL); + + // Trigger LDMA transfer on IADC scan completion + LDMA_TransferCfg_t transferCfg = + LDMA_TRANSFER_CFG_PERIPHERAL(ldmaPeripheralSignal_IADC0_IADC_SCAN); + + params->descriptor = + (LDMA_Descriptor_t)LDMA_DESCRIPTOR_LINKREL_P2M_WORD(&(params->adc->SCANFIFODATA), + params->buffer, + params->noAdcChannels, + 0); + + DMADRV_LdmaStartTransfer(params->dmaChannel, + &transferCfg, + ¶ms->descriptor, + fn, + params); +} + +static void _currentSenseInitScan( + EFR32CurrentSenseParams *params +) { + if (!params || !params->adc) return; + + // Enable Clock + CMU_ClockEnable(cmuClock_IADC0, true); + CMU_ClockEnable(cmuClock_GPIO, true); + + // Use the FSRC0 as the IADC clock so it can run in EM2 + CMU_ClockSelectSet(cmuClock_IADCCLK, cmuSelect_FSRCO); + + for (uint8_t i = 0; i < params->noAdcChannels; ++i) { + GPIO_PinModeSet(params->inst[i].port, params->inst[i].pin, gpioModeDisabled, 0); + } + + IADC_Init_t init = IADC_INIT_DEFAULT; + init.warmup = iadcWarmupKeepWarm; + init.srcClkPrescale = IADC_calcSrcClkPrescale(params->adc, _CLK_SRC_ADC_FREQ, 0); + + IADC_CfgReference_t adcRef; + switch (params->vRef) { + case 1200: adcRef = iadcCfgReferenceInt1V2; break; + case 1250: adcRef = iadcCfgReferenceExt1V25; break; + case 3300: adcRef = iadcCfgReferenceVddx; break; + case 2640: adcRef = iadcCfgReferenceVddX0P8Buf; break; + default: return; + } + + IADC_AllConfigs_t allConfigs = IADC_ALLCONFIGS_DEFAULT; + allConfigs.configs[0].reference = adcRef; + allConfigs.configs[0].vRef = params->vRef; + allConfigs.configs[0].adcClkPrescale = IADC_calcAdcClkPrescale(params->adc, + _CLK_ADC_FREQ, + 0, + iadcCfgModeNormal, + init.srcClkPrescale); + + // Reset the ADC + IADC_reset(params->adc); + + // Only configure the ADC if it is not already running + if (params->adc->CTRL == _IADC_CTRL_RESETVALUE) { + IADC_init(params->adc, &init, &allConfigs); + } + + IADC_InitScan_t initScan = IADC_INITSCAN_DEFAULT; + if ((params->mode == CS_LO_SIDE) || (params->mode == CS_HI_SIDE)) { + // Note: CS_HI_SIDE not implemented + initScan.triggerSelect = iadcTriggerSelPrs0PosEdge; + } + initScan.fifoDmaWakeup = true; + + IADC_ScanTable_t scanTable = IADC_SCANTABLE_DEFAULT; + for (uint8_t i = 0; i < params->noAdcChannels; ++i) { + scanTable.entries[i].posInput = IADC_portPinToPosInput(params->inst[i].port, params->inst[i].pin); + scanTable.entries[i].negInput = iadcNegInputGnd; + scanTable.entries[i].includeInScan = true; + } + + // Initialize IADC + IADC_init(params->adc, &init, &allConfigs); + + // Initialize Scan + IADC_initScan(params->adc, &initScan, &scanTable); + + // Allocate + for (uint8_t i = 0; i < params->noAdcChannels; ++i) { + _adcBusAllocate(params->inst[i].port, params->inst[i].pin); + } +} + +static void _currentSenseConfig( + EFR32CurrentSenseParams *params, + int adcPins[SILABS_MAX_ANALOG] +) { + if (!params) return; + + uint8_t noAdcChannels = 0; + for (int i = 0; i < SILABS_MAX_ANALOG; ++i) { + if (!_isset(adcPins[i])) continue; + if (params->firstIndex == 0xFF) params->firstIndex = i; + _adcConfig(¶ms->inst[noAdcChannels], adcPins[i]); + params->pins[noAdcChannels] = adcPins[i]; + ++noAdcChannels; + } + + params->noAdcChannels = noAdcChannels; +} + +static void _currentSenseDeinit( + EFR32CurrentSenseParams *params +) { + if (!params) return; + + DMADRV_StopTransfer(params->dmaChannel); + DMADRV_FreeChannel(params->dmaChannel); + + IADC_reset(params->adc); +} + +static void _currentSenseStartScan( + EFR32CurrentSenseParams *params +) { + if (!params || !params->adc) return; + + IADC_command(params->adc, iadcCmdStartScan); +} + +static void _currentSenseStopScan( + EFR32CurrentSenseParams *params +) { + if (!params) return; + + IADC_command(params->adc, iadcCmdStopScan); +} + +static void _currentSenseStopTranfer( + EFR32CurrentSenseParams *params +) { + if (!params || !params->adc) return; + + DMADRV_PauseTransfer(params->dmaChannel); +} + +static void _currentSenseStartTranfer( + EFR32CurrentSenseParams *params +) { + if (!params || !params->adc) return; + + DMADRV_ResumeTransfer(params->dmaChannel); +} + +//////////////////////////////////////////////////////////////////////////////// +// Low Side Mode +//////////////////////////////////////////////////////////////////////////////// + +float _readADCVoltageLowSide( + const int pin, + const void *cs_params +) { + EFR32CurrentSenseParams *params = (EFR32CurrentSenseParams *) cs_params; + if (!params) return 0.0f; + + return _readAdc(params, pin); +} + +void* _configureADCLowSide( + const void* driver_params, + const int pinA, + const int pinB, + const int pinC +) { + _UNUSED(driver_params); + + EFR32CurrentSenseParams *params = new EFR32CurrentSenseParams { + .adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION), + .firstIndex = 0xFF, + .noAdcChannels = 0, + .vRef = SILABS_ADC_VREF, + .prsChannel = SILABS_ADC_PRS_CHANNEL, + .mode = CS_LO_SIDE, + .adc = SILABS_DEFAULT_ADC_PERPHERAL, + }; + + if (!params) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED; + + int adcPins[3] = { pinA, pinB, pinC }; + + _currentSenseConfig(params, adcPins); + _currentSenseInitScan(params); + _currentSenseInitDMA(params, NULL, params); + _currentSenseStartScan(params); + + return params; +} + +void* _driverSyncLowSide( + void *driver_params, + void *cs_params +) { + EFR32DriverParams *driver = (EFR32DriverParams *) driver_params; + EFR32CurrentSenseParams *params = (EFR32CurrentSenseParams *) cs_params; + + if (!driver || !params) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED; + + uint32_t prsSource, prsSignal; + + CMU_ClockEnable(cmuClock_PRS, true); + + _getPrsSourceAndUnderflowSignal(driver->inst[0].h.timer, &prsSource, &prsSignal); + PRS_SourceAsyncSignalSet(params->prsChannel, prsSource, prsSignal); + PRS_ConnectConsumer(params->prsChannel, prsTypeAsync, prsConsumerIADC0_SCANTRIGGER); + + return cs_params; +} + +//////////////////////////////////////////////////////////////////////////////// +// Inline Mode +//////////////////////////////////////////////////////////////////////////////// + +float _readADCVoltageInline( + const int pin, + const void *cs_params +) { + EFR32CurrentSenseParams *params = (EFR32CurrentSenseParams *) cs_params; + if (!params || !_isset(pin) || (params->firstIndex == 0xFF)) return 0.0f; + + if (params->pins[params->firstIndex] == pin) { + CORE_DECLARE_IRQ_STATE; + CORE_ENTER_ATOMIC(); + params->dataReady = false; + CORE_EXIT_ATOMIC(); + + _currentSenseStartScan(params); + + while (!params->dataReady) {} + } + + return _readAdc(params, pin); +} + +void* _configureADCInline( + const void* driver_params, + const int pinA, + const int pinB, + const int pinC +) { + _UNUSED(driver_params); + + EFR32CurrentSenseParams *params = new EFR32CurrentSenseParams { + .adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION), + .firstIndex = 0xFF, + .noAdcChannels = 0, + .vRef = SILABS_ADC_VREF, + .prsChannel = SILABS_ADC_PRS_CHANNEL, + .mode = CS_INLINE, + .adc = SILABS_DEFAULT_ADC_PERPHERAL, + }; + + if (!params) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED; + + int adcPins[3] = { pinA, pinB, pinC }; + + _currentSenseConfig(params, adcPins); + _currentSenseInitScan(params); + _currentSenseInitDMA(params, _dmaTransferFinishedCb, params); + + return params; +} + +#endif \ No newline at end of file diff --git a/src/current_sense/hardware_specific/silabs/efr32_mcu.h b/src/current_sense/hardware_specific/silabs/efr32_mcu.h new file mode 100644 index 00000000..40657ec4 --- /dev/null +++ b/src/current_sense/hardware_specific/silabs/efr32_mcu.h @@ -0,0 +1,58 @@ +#ifndef EFR32_CURRENTSENSE_MCU_H +#define EFR32_CURRENTSENSE_MCU_H + +#include "../../hardware_api.h" + +#if defined(ARDUINO_ARCH_SILABS) +#include +#include +#include +#include + +#ifndef SILABS_DEFAULT_ADC_PERPHERAL +#define SILABS_DEFAULT_ADC_PERPHERAL IADC0 +#endif + +#ifndef SILABS_ADC_VREF +#define SILABS_ADC_VREF 3300 +#endif + +#ifndef SILABS_ADC_PRS_CHANNEL +#define SILABS_ADC_PRS_CHANNEL 1 +#endif + +#ifndef SILABS_MAX_ANALOG +#define SILABS_MAX_ANALOG 3 +#endif + +typedef enum { + CS_INLINE, + CS_LO_SIDE, + CS_HI_SIDE, +} EFR32CurrentSenseMode; + +typedef struct { + uint8_t port; + uint8_t pin; +} EFR32AdcInstance; + +typedef struct { + int pins[SILABS_MAX_ANALOG]; + float adc_voltage_conv; + EFR32AdcInstance inst[SILABS_MAX_ANALOG]; + uint8_t firstIndex; + uint8_t noAdcChannels; + volatile bool dataReady; + uint32_t id; + uint32_t buffer[SILABS_MAX_ANALOG]; + uint32_t vRef; + unsigned int dmaChannel; + unsigned int prsChannel; + EFR32CurrentSenseMode mode; + IADC_TypeDef *adc; + LDMA_Descriptor_t descriptor; +} EFR32CurrentSenseParams; + +#endif + +#endif \ No newline at end of file diff --git a/src/drivers/hardware_specific/silabs/efr32_mcu.cpp b/src/drivers/hardware_specific/silabs/efr32_mcu.cpp new file mode 100644 index 00000000..2965a5d6 --- /dev/null +++ b/src/drivers/hardware_specific/silabs/efr32_mcu.cpp @@ -0,0 +1,368 @@ +// File: efr32_mcu.cpp + +#if defined(ARDUINO_ARCH_SILABS) + +#include +#include +#include "efr32_pwm.h" +#include "efr32_mcu.h" + +void _getPrsSourceAndUnderflowSignal( + TIMER_TypeDef *timer, + uint32_t *source, + uint32_t *signal +) { + if (!timer || !source || !signal) return; + + switch ((uint32_t) timer) { + case TIMER0_BASE: + *source = PRS_ASYNC_CH_CTRL_SOURCESEL_TIMER0; + *signal = PRS_ASYNC_CH_CTRL_SIGSEL_TIMER0UF; + break; + + case TIMER1_BASE: + *source = PRS_ASYNC_CH_CTRL_SOURCESEL_TIMER1; + *signal = PRS_ASYNC_CH_CTRL_SIGSEL_TIMER1UF; + break; + + case TIMER2_BASE: + *source = PRS_ASYNC_CH_CTRL_SOURCESEL_TIMER2; + *signal = PRS_ASYNC_CH_CTRL_SIGSEL_TIMER2UF; + break; + + default: + break; + } +} + +// Callbacks +static void _alignPWMTimers( + TIMER_InitCC_TypeDef *initCC, + void *params +) { + EFR32PwmInstance *p = (EFR32PwmInstance*)params; + if (!p || !initCC) return; + + CMU_ClockEnable(cmuClock_PRS, true); + + uint32_t prsSource, prsSignal; + + initCC->prsInputType = timerPrsInputAsyncPulse; + initCC->prsInput = true; + initCC->prsSel = SILABS_PWM_PRS_CHANNEL; + + _getPrsSourceAndUnderflowSignal(p->h.timer, &prsSource, &prsSignal); + PRS_SourceAsyncSignalSet(SILABS_PWM_PRS_CHANNEL, prsSource, prsSignal); +} + +static void _configPWMMode( + TIMER_Init_TypeDef *init, + void *params +) { + if (!init) return; + _UNUSED(params); + init->mode = timerModeUpDown; +} + +static void _alignPWMStart( + TIMER_Init_TypeDef *init, + void *params +) { + if (!init) return; + _UNUSED(params); + init->mode = timerModeUpDown; + init->riseAction = timerInputActionReloadStart; +} + +static void _setSinglePhaseState(EFR32PwmInstance *inst, PhaseState state) { + if (!inst) return; + + switch (state) { + case PhaseState::PHASE_OFF: + pwmOff(inst); + break; + + default: + pwmOn(inst); + break; + } +} + +void *_configure1PWM(long pwm_frequency, const int pinA) { + EFR32DriverParams* params = new EFR32DriverParams; + if (!params) return SIMPLEFOC_DRIVER_INIT_FAILED; + + if (!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = SILABS_DEFAULT_PWM_FREQUENCY; + else pwm_frequency = _constrain(pwm_frequency, 0, SILABS_DEFAULT_PWM_FREQUENCY); + + params->pwm_frequency = pwm_frequency; + params->noPwmChannel = 1; + + // Ensure all PWMs use the same TIMER instance + pwmHiConfig(¶ms->inst[0], SILABS_DEFAULT_PWM_PERPHERAL, pinA, 0); + + // Initialize PWM + EFR32PwmConfig pwmConfig; + pwmConfig.frequency = pwm_frequency; + pwmConfig.polarity = PWM_P_ACTIVE_LOW; + pwmConfig.outInvert = true; + + pwmHiInit(¶ms->inst[0], &pwmConfig, NULL, NULL); + + // PWM On + pwmHiOn(¶ms->inst[0]); + + // Start PWM + pwmStart(¶ms->inst[0], _configPWMMode, NULL); + + return params; +} + +void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) { + EFR32DriverParams *params = new EFR32DriverParams; + if (!params) return SIMPLEFOC_DRIVER_INIT_FAILED; + + if (!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = SILABS_DEFAULT_PWM_FREQUENCY; + else pwm_frequency = _constrain(pwm_frequency, 0, SILABS_DEFAULT_PWM_FREQUENCY); + + params->pwm_frequency = pwm_frequency; + params->noPwmChannel = 2; + + // Ensure all PWMs use the same TIMER instance + pwmHiConfig(¶ms->inst[0], SILABS_DEFAULT_PWM_PERPHERAL, pinA, 0); + pwmHiConfig(¶ms->inst[1], SILABS_DEFAULT_PWM_PERPHERAL, pinB, 1); + + // Initialize PWM + EFR32PwmConfig pwmConfig; + pwmConfig.frequency = pwm_frequency << 1; + pwmConfig.polarity = PWM_P_ACTIVE_LOW; + pwmConfig.outInvert = true; + + pwmHiInit(¶ms->inst[0], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[1], &pwmConfig, NULL, NULL); + + // PWM On + pwmHiOn(¶ms->inst[0]); + pwmHiOn(¶ms->inst[1]); + + // Start PWM + pwmStart(¶ms->inst[0], _configPWMMode, NULL); + + return params; +} + +void* _configure3PWM( + long pwm_frequency, + const int pinA, + const int pinB, + const int pinC +) { + EFR32DriverParams *params = new EFR32DriverParams; + if (!params) return SIMPLEFOC_DRIVER_INIT_FAILED; + + if (!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = SILABS_DEFAULT_PWM_FREQUENCY; + else pwm_frequency = _constrain(pwm_frequency, 0, SILABS_DEFAULT_PWM_FREQUENCY); + + params->pwm_frequency = pwm_frequency; + params->noPwmChannel = 3; + + // Ensure all PWMs use the same TIMER instance + pwmHiConfig(¶ms->inst[0], SILABS_DEFAULT_PWM_PERPHERAL, pinA, 0); + pwmHiConfig(¶ms->inst[1], SILABS_DEFAULT_PWM_PERPHERAL, pinB, 1); + pwmHiConfig(¶ms->inst[2], SILABS_DEFAULT_PWM_PERPHERAL, pinC, 2); + + // Initialize PWM + EFR32PwmConfig pwmConfig; + pwmConfig.frequency = pwm_frequency << 1; + pwmConfig.polarity = PWM_P_ACTIVE_LOW; + pwmConfig.outInvert = true; + + pwmHiInit(¶ms->inst[0], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[1], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[2], &pwmConfig, NULL, NULL); + + // PWM On + pwmHiOn(¶ms->inst[0]); + pwmHiOn(¶ms->inst[1]); + pwmHiOn(¶ms->inst[2]); + + // Start PWM + pwmStart(¶ms->inst[0], _configPWMMode, NULL); + + return params; +} + +void* _configure4PWM( + long pwm_frequency, + const int pin1A, + const int pin1B, + const int pin2A, + const int pin2B +) { + EFR32DriverParams *params = new EFR32DriverParams; + if (!params) return SIMPLEFOC_DRIVER_INIT_FAILED; + + if (!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = SILABS_DEFAULT_PWM_FREQUENCY; + else pwm_frequency = _constrain(pwm_frequency, 0, SILABS_DEFAULT_PWM_FREQUENCY); + + params->pwm_frequency = pwm_frequency; + params->noPwmChannel = 4; + + // Ensure all PWMs use the same TIMER instance + pwmHiConfig(¶ms->inst[0], SILABS_DEFAULT_PWM_PERPHERAL, pin1A, 0); + pwmHiConfig(¶ms->inst[1], SILABS_DEFAULT_PWM_PERPHERAL, pin1B, 1); + pwmHiConfig(¶ms->inst[2], SILABS_DEFAULT_PWM_PERPHERAL, pin2A, 2); + pwmHiConfig(¶ms->inst[3], SILABS_SECOND_PWM_PERPHERAL , pin2B, 0); + + // Initialize PWM + EFR32PwmConfig pwmConfig; + pwmConfig.frequency = pwm_frequency << 1; + pwmConfig.polarity = PWM_P_ACTIVE_LOW; + pwmConfig.outInvert = true; + + pwmHiInit(¶ms->inst[0], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[1], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[2], &pwmConfig, NULL, NULL); + pwmHiInit(¶ms->inst[3], &pwmConfig, _alignPWMTimers, ¶ms->inst[0]); + + // PWM On + pwmHiOn(¶ms->inst[0]); + pwmHiOn(¶ms->inst[1]); + pwmHiOn(¶ms->inst[2]); + pwmHiOn(¶ms->inst[3]); + + // Start PWM + pwmStart(¶ms->inst[0], _configPWMMode, NULL); + pwmStart(¶ms->inst[3], _alignPWMStart, NULL); + + return params; +} + +void* _configure6PWM( + long pwm_frequency, + float dead_zone, + const int pinA_h, + const int pinA_l, + const int pinB_h, + const int pinB_l, + const int pinC_h, + const int pinC_l +) { + EFR32DriverParams *params = new EFR32DriverParams; + if (!params) return SIMPLEFOC_DRIVER_INIT_FAILED; + + if (!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = SILABS_DEFAULT_PWM_FREQUENCY; + else pwm_frequency = _constrain(pwm_frequency, 0, SILABS_DEFAULT_PWM_FREQUENCY); + + params->pwm_frequency = pwm_frequency; + params->dead_zone = (dead_zone == NOT_SET) ? SILABS_DEFAULT_DEAD_ZONE : dead_zone; + params->lowside = true; + params->noPwmChannel = 3; + + // Ensure all PWMs use the same TIMER instance + pwmHiConfig(¶ms->inst[0], SILABS_DEFAULT_PWM_PERPHERAL, pinA_h, 0); + pwmLoConfig(¶ms->inst[0], pinA_l); + + pwmHiConfig(¶ms->inst[1], SILABS_DEFAULT_PWM_PERPHERAL, pinB_h, 1); + pwmLoConfig(¶ms->inst[1], pinB_l); + + pwmHiConfig(¶ms->inst[2], SILABS_DEFAULT_PWM_PERPHERAL, pinC_h, 2); + pwmLoConfig(¶ms->inst[2], pinC_l); + + // Initialize PWM + EFR32PwmConfig pwmConfig; + pwmConfig.frequency = pwm_frequency << 1; + pwmConfig.polarity = PWM_P_ACTIVE_LOW; + pwmConfig.outInvert = true; + + pwmInit(¶ms->inst[0], &pwmConfig, NULL, NULL); + pwmInit(¶ms->inst[1], &pwmConfig, NULL, NULL); + pwmInit(¶ms->inst[2], &pwmConfig, NULL, NULL); + + // Dead Time PWM + uint32_t deadTimeNs = (float) (1e9f / pwm_frequency) * dead_zone; + EFR32PwmDeadTimeConfig deadTimeConfig; + deadTimeConfig.deadTimeNs = deadTimeNs >> 1; + deadTimeConfig.outputMask = TIMER_DTOGEN_DTOGCC0EN + | TIMER_DTOGEN_DTOGCC1EN + | TIMER_DTOGEN_DTOGCC2EN + | TIMER_DTOGEN_DTOGCDTI0EN + | TIMER_DTOGEN_DTOGCDTI1EN + | TIMER_DTOGEN_DTOGCDTI2EN; + pwmDeadTimeInit(¶ms->inst[0], &deadTimeConfig); + + // PWM On + pwmOn(¶ms->inst[0]); + pwmOn(¶ms->inst[1]); + pwmOn(¶ms->inst[2]); + + // Start PWM + pwmStart(¶ms->inst[0], _configPWMMode, NULL); + + return params; +} + +void _writeDutyCycle1PWM(float dc_a, void* params) { + EFR32DriverParams *p = (EFR32DriverParams*) params; + if (!p) return; + + pwmHiSetDutyCycle(&p->inst[0], dc_a * 100.0f); +} + +void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) { + EFR32DriverParams *p = (EFR32DriverParams*) params; + if (!p) return; + + pwmHiSetDutyCycle(&p->inst[0], dc_a * 100.0f); + pwmHiSetDutyCycle(&p->inst[1], dc_b * 100.0f); +} + +void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params) { + EFR32DriverParams *p = (EFR32DriverParams*) params; + if (!p) return; + + pwmHiSetDutyCycle(&p->inst[0], dc_a * 100.0f); + pwmHiSetDutyCycle(&p->inst[1], dc_b * 100.0f); + pwmHiSetDutyCycle(&p->inst[2], dc_c * 100.0f); +} + +void _writeDutyCycle4PWM( + float dc_1a, + float dc_1b, + float dc_2a, + float dc_2b, + void* params +) { + EFR32DriverParams *p = (EFR32DriverParams*) params; + if (!p) return; + + pwmHiSetDutyCycle(&p->inst[0], dc_1a * 100.0f); + pwmHiSetDutyCycle(&p->inst[1], dc_1b * 100.0f); + pwmHiSetDutyCycle(&p->inst[2], dc_2a * 100.0f); + pwmHiSetDutyCycle(&p->inst[3], dc_2b * 100.0f); +} + +void _writeDutyCycle6PWM( + float dc_a, + float dc_b, + float dc_c, + PhaseState *phase_state, + void* params +) { + EFR32DriverParams *p = (EFR32DriverParams*) params; + if (!p || !phase_state) return; + + _setSinglePhaseState(&p->inst[0], phase_state[0]); + if (phase_state[0] == PhaseState::PHASE_OFF) dc_a = 0.0f; + pwmHiSetDutyCycle(&p->inst[0], dc_a * 100); + + _setSinglePhaseState(&p->inst[1], phase_state[1]); + if (phase_state[1] == PhaseState::PHASE_OFF) dc_b = 0.0f; + pwmHiSetDutyCycle(&p->inst[1], dc_b * 100.0f); + + _setSinglePhaseState(&p->inst[2], phase_state[2]); + if (phase_state[2] == PhaseState::PHASE_OFF) dc_c = 0.0f; + pwmHiSetDutyCycle(&p->inst[2], dc_c * 100.0f); +} + +#endif \ No newline at end of file diff --git a/src/drivers/hardware_specific/silabs/efr32_mcu.h b/src/drivers/hardware_specific/silabs/efr32_mcu.h new file mode 100644 index 00000000..4b00422a --- /dev/null +++ b/src/drivers/hardware_specific/silabs/efr32_mcu.h @@ -0,0 +1,39 @@ +#ifndef EFR32_DRIVER_MCU_H +#define EFR32_DRIVER_MCU_H + +#include "../../hardware_api.h" + +#if defined(ARDUINO_ARCH_SILABS) +#include "efr32_pwm.h" + +#ifndef SILABS_DEFAULT_PWM_PERPHERAL +#define SILABS_DEFAULT_PWM_PERPHERAL TIMER0 +#endif + +#ifndef SILABS_SECOND_PWM_PERPHERAL +#define SILABS_SECOND_PWM_PERPHERAL TIMER1 +#endif + +#ifndef SILABS_PWM_PRS_CHANNEL +#define SILABS_PWM_PRS_CHANNEL 0 +#endif + +#ifndef SILABS_DEFAULT_PWM_FREQUENCY +#define SILABS_DEFAULT_PWM_FREQUENCY 50000 +#endif + +#ifndef SILABS_DEFAULT_DEAD_ZONE +#define SILABS_DEFAULT_DEAD_ZONE 0.02f +#endif + +typedef struct EFR32DriverParams { + EFR32PwmInstance inst[4]; + uint8_t noPwmChannel; + bool lowside; + long pwm_frequency; + float dead_zone; +} EFR32DriverParams; + +#endif + +#endif diff --git a/src/drivers/hardware_specific/silabs/efr32_pwm.cpp b/src/drivers/hardware_specific/silabs/efr32_pwm.cpp new file mode 100644 index 00000000..3884220f --- /dev/null +++ b/src/drivers/hardware_specific/silabs/efr32_pwm.cpp @@ -0,0 +1,310 @@ +#if defined(ARDUINO_ARCH_SILABS) + +#include +#include +#include +#include +#include +#include "efr32_pwm.h" + +static CMU_Clock_TypeDef _getTimerClock(TIMER_TypeDef *timer) { +#if defined(_CMU_HFCLKSEL_MASK) || defined(_CMU_CMD_HFCLKSEL_MASK) + CMU_Clock_TypeDef timerClock = cmuClock_HF; +#elif defined(_CMU_SYSCLKCTRL_MASK) + CMU_Clock_TypeDef timerClock = cmuClock_SYSCLK; +#else +#error "Unknown root of clock tree" +#endif + + switch ((uint32_t)timer) { +#if defined(TIMER0_BASE) + case TIMER0_BASE: + timerClock = cmuClock_TIMER0; + break; +#endif +#if defined(TIMER1_BASE) + case TIMER1_BASE: + timerClock = cmuClock_TIMER1; + break; +#endif +#if defined(TIMER2_BASE) + case TIMER2_BASE: + timerClock = cmuClock_TIMER2; + break; +#endif +#if defined(TIMER3_BASE) + case TIMER3_BASE: + timerClock = cmuClock_TIMER3; + break; +#endif +#if defined(TIMER4_BASE) + case TIMER4_BASE: + timerClock = cmuClock_TIMER4; + break; +#endif +#if defined(TIMER5_BASE) + case TIMER5_BASE: + timerClock = cmuClock_TIMER5; + break; +#endif +#if defined(TIMER6_BASE) + case TIMER6_BASE: + timerClock = cmuClock_TIMER6; + break; +#endif +#if defined(WTIMER0_BASE) + case WTIMER0_BASE: + timerClock = cmuClock_WTIMER0; + break; +#endif +#if defined(WTIMER1_BASE) + case WTIMER1_BASE: + timerClock = cmuClock_WTIMER1; + break; +#endif +#if defined(WTIMER2_BASE) + case WTIMER2_BASE: + timerClock = cmuClock_WTIMER2; + break; +#endif +#if defined(WTIMER3_BASE) + case WTIMER3_BASE: + timerClock = cmuClock_WTIMER3; + break; +#endif + default: + break; + } + return timerClock; +} + +void pwmHiConfig( + EFR32PwmInstance *inst, + TIMER_TypeDef *timer, + const int pin, + const uint8_t channel +) { + if (!inst) return; + + inst->h.timer = timer; + inst->h.port = getSilabsPortFromArduinoPin(pinToPinName(pin)); + inst->h.pin = getSilabsPinFromArduinoPin(pinToPinName(pin)); + inst->h.channel = channel; +} + +void pwmHiInit( + EFR32PwmInstance *inst, + EFR32PwmConfig *config, + prevTimerInitCCFn fn, + void *params +) { + if (!inst || !config) return; + + // Enable Timer Clock + CMU_Clock_TypeDef timerClock = _getTimerClock(inst->h.timer); + CMU_ClockEnable(timerClock, true); + + // Set PWM pin as output + CMU_ClockEnable(cmuClock_GPIO, true); + GPIO_PinModeSet((GPIO_Port_TypeDef)inst->h.port, + inst->h.pin, + gpioModePushPull, + config->polarity); + + // Set CC channel parameters + TIMER_InitCC_TypeDef initCC = TIMER_INITCC_DEFAULT; + initCC.mode = timerCCModePWM; + if (config->outInvert) initCC.outInvert = true; + if (fn) fn(&initCC, params); + + TIMER_InitCC(inst->h.timer, inst->h.channel, &initCC); + + volatile uint32_t *routeRegister = &GPIO->TIMERROUTE[TIMER_NUM(inst->h.timer)].CC0ROUTE; + routeRegister += inst->h.channel; + *routeRegister = (inst->h.port << _GPIO_TIMER_CC0ROUTE_PORT_SHIFT) + | (inst->h.pin << _GPIO_TIMER_CC0ROUTE_PIN_SHIFT); + + // Configure TIMER frequency + uint32_t top = (CMU_ClockFreqGet(timerClock) / (config->frequency)) - 1U; + TIMER_TopSet(inst->h.timer, top); + + // Set initial duty cycle to 0% + TIMER_CompareSet(inst->h.timer, inst->h.channel, 0U); +} + +void pwmHiDeinit( + EFR32PwmInstance *inst +) { + if (!inst) return; + + pwmHiOff(inst); + + volatile uint32_t *routeRegister = &GPIO->TIMERROUTE[TIMER_NUM(inst->h.timer)].CC0ROUTE; + routeRegister += inst->h.channel; + *routeRegister = 0; + + TIMER_Reset(inst->h.timer); + GPIO_PinModeSet((GPIO_Port_TypeDef)inst->h.port, + inst->h.pin, + gpioModeDisabled, + 0); + CMU_Clock_TypeDef timerClock = _getTimerClock(inst->h.timer); + CMU_ClockEnable(timerClock, false); +} + +void pwmHiOn( + EFR32PwmInstance *inst +) { + if (!inst) return; + GPIO->TIMERROUTE_SET[TIMER_NUM(inst->h.timer)].ROUTEEN = 1 << (inst->h.channel + _GPIO_TIMER_ROUTEEN_CC0PEN_SHIFT); +} + +void pwmHiOff( + EFR32PwmInstance *inst +) { + if (!inst) return; + GPIO->TIMERROUTE_CLR[TIMER_NUM(inst->h.timer)].ROUTEEN = 1 << (inst->h.channel + _GPIO_TIMER_ROUTEEN_CC0PEN_SHIFT); +} + +void pwmHiSetDutyCycle( + EFR32PwmInstance *inst, + float percent +) { + if (!inst || (percent > 100.0f)) return; + uint32_t top = TIMER_TopGet(inst->h.timer); + volatile bool outInvert = inst->h.timer->CC[inst->h.channel].CTRL & TIMER_CC_CTRL_OUTINV; + if (outInvert) percent = 100 - percent; + TIMER_CompareBufSet(inst->h.timer, inst->h.channel, (uint32_t) (top * percent) / 100); +} + +float pwmHiGetDutyCycle( + EFR32PwmInstance *inst +) { + if (!inst) return 0; + uint32_t top = TIMER_TopGet(inst->h.timer); + uint32_t compare = TIMER_CaptureGet(inst->h.timer, inst->h.channel); + volatile bool outInvert = inst->h.timer->CC[inst->h.channel].CTRL & TIMER_CC_CTRL_OUTINV; + float percent = (float)((compare * 100) / top); + return outInvert ? (100 - percent) : percent; +} + +void pwmLoConfig( + EFR32PwmInstance *inst, + const int pin +) { + if (!inst) return; + inst->l.port = getSilabsPortFromArduinoPin(pinToPinName(pin)); + inst->l.pin = getSilabsPinFromArduinoPin(pinToPinName(pin)); +} + +void pwmLoInit( + EFR32PwmInstance *inst +) { + if (!inst) return; + + // Low side PWM + CMU_ClockEnable(cmuClock_GPIO, true); + GPIO_PinModeSet((GPIO_Port_TypeDef)inst->l.port, + inst->l.pin, + gpioModePushPull, + 0); + + volatile uint32_t *routeRegister = &GPIO->TIMERROUTE[TIMER_NUM(inst->h.timer)].CDTI0ROUTE; + routeRegister += inst->h.channel; + *routeRegister = (inst->l.port << _GPIO_TIMER_CDTI0ROUTE_PORT_SHIFT) + | (inst->l.pin << _GPIO_TIMER_CDTI0ROUTE_PIN_SHIFT); +} + +void pwmLoDeinit( + EFR32PwmInstance *inst +) { + if (!inst) return; + + pwmLoOff(inst); + + volatile uint32_t *routeRegister = &GPIO->TIMERROUTE[TIMER_NUM(inst->h.timer)].CDTI0ROUTE; + routeRegister += inst->h.channel; + *routeRegister = 0; + + GPIO_PinModeSet((GPIO_Port_TypeDef)inst->l.port, + inst->l.pin, + gpioModeDisabled, + 0); +} + +void pwmLoOn( + EFR32PwmInstance *inst +) { + if (!inst) return; + GPIO->TIMERROUTE_SET[TIMER_NUM(inst->h.timer)].ROUTEEN |= 1 << (inst->h.channel + _GPIO_TIMER_ROUTEEN_CCC0PEN_SHIFT); +} + +void pwmLoOff( + EFR32PwmInstance *inst +) { + if (!inst) return; + GPIO->TIMERROUTE_CLR[TIMER_NUM(inst->h.timer)].ROUTEEN |= 1 << (inst->h.channel + _GPIO_TIMER_ROUTEEN_CCC0PEN_SHIFT); +} + +void pwmInit( + EFR32PwmInstance *inst, + EFR32PwmConfig *config, + prevTimerInitCCFn fn, + void *params +) { + if (!inst || !config) return; + pwmHiInit(inst, config, fn, params); + pwmLoInit(inst); +} + +void pwmDeinit( + EFR32PwmInstance *inst +) { + if (!inst) return; + pwmHiDeinit(inst); + pwmLoDeinit(inst); +} + +void pwmOff(EFR32PwmInstance *inst) { + if (!inst) return; + pwmHiOff(inst); + pwmLoOff(inst); +} + +void pwmOn(EFR32PwmInstance *inst) { + if (!inst) return; + pwmHiOn(inst); + pwmLoOn(inst); +} + +void pwmStart(EFR32PwmInstance *inst, prevTimerInitFn fn, void *params) { + if (!inst) return; + + // Initialize TIMER + TIMER_Init_TypeDef timerInit = TIMER_INIT_DEFAULT; + if (fn) fn(&timerInit, params); + TIMER_Init(inst->h.timer, &timerInit); +} + +void pwmDeadTimeInit( + EFR32PwmInstance *inst, + EFR32PwmDeadTimeConfig *config +) { + if (!inst || !config) return; + + // Enable Timer Clock + CMU_Clock_TypeDef timerClock = _getTimerClock(inst->h.timer); + CMU_ClockEnable(timerClock, true); + + unsigned int dtiTime = (CMU_ClockFreqGet(timerClock) / 1e3f) * config->deadTimeNs / 1e6f; + if (dtiTime > 64) dtiTime = SILABBS_DEFAULT_DEAD_TIME; + + TIMER_InitDTI_TypeDef initDTI = TIMER_INITDTI_DEFAULT; + initDTI.riseTime = dtiTime; + initDTI.fallTime = dtiTime; + initDTI.outputsEnableMask = config->outputMask; + + TIMER_InitDTI(inst->h.timer, &initDTI); +} + +#endif \ No newline at end of file diff --git a/src/drivers/hardware_specific/silabs/efr32_pwm.h b/src/drivers/hardware_specific/silabs/efr32_pwm.h new file mode 100644 index 00000000..a4e1fee7 --- /dev/null +++ b/src/drivers/hardware_specific/silabs/efr32_pwm.h @@ -0,0 +1,121 @@ +#ifndef EFR32_DRIVER_PWM_MCU_H +#define EFR32_DRIVER_PWM_MCU_H + +#if defined(ARDUINO_ARCH_SILABS) + +#include + +#ifndef SILABBS_DEFAULT_DEAD_TIME +#define SILABBS_DEFAULT_DEAD_TIME 3 +#endif + +typedef void (*prevTimerInitCCFn)(TIMER_InitCC_TypeDef*, void *params); +typedef void (*prevTimerInitFn)(TIMER_Init_TypeDef*, void *params); + +typedef enum { + PWM_P_ACTIVE_HIGH = 0, + PWM_P_ACTIVE_LOW = 1 +} EFR32PwmPolarity; + +typedef struct { + int frequency; /**< PWM frequency */ + bool outInvert; /**< Invert output */ + EFR32PwmPolarity polarity; /**< PWM polarity */ +} EFR32PwmConfig; + +typedef struct { + uint32_t deadTimeNs; + uint32_t outputMask; +} EFR32PwmDeadTimeConfig; + +typedef struct { + TIMER_TypeDef *timer; /**< TIMER instance */ + uint8_t channel; /**< TIMER channel */ + uint8_t port; /**< GPIO port */ + uint8_t pin; /**< GPIO pin */ +} EFR32PwmHiInstance; + +typedef struct { + uint8_t port; + uint8_t pin; +} EFR32PwmLoInstance; + +typedef struct { + EFR32PwmHiInstance h; + EFR32PwmLoInstance l; +} EFR32PwmInstance; + +// High Side +void pwmHiConfig( + EFR32PwmInstance *inst, + TIMER_TypeDef *timer, + const int pin, + const uint8_t channel); + +void pwmHiInit( + EFR32PwmInstance *inst, + EFR32PwmConfig *config, + prevTimerInitCCFn fn, + void *params); + +void pwmHiDeinit( + EFR32PwmInstance *inst); + +void pwmHiOn( + EFR32PwmInstance *inst); + +void pwmHiOff( + EFR32PwmInstance *inst); + +void pwmHiSetDutyCycle( + EFR32PwmInstance *inst, + float percent); + +float pwmHiGetDutyCycle( + EFR32PwmInstance *inst); + +// Low Side +void pwmLoConfig( + EFR32PwmInstance *inst, + const int pin); + +void pwmLoInit( + EFR32PwmInstance *inst); + +void pwmLoDeinit( + EFR32PwmInstance *inst); + +void pwmLoOn( + EFR32PwmInstance *inst); + +void pwmLoOff( + EFR32PwmInstance *inst); + +// Pwm +void pwmInit( + EFR32PwmInstance *inst, + EFR32PwmConfig *cfg, + prevTimerInitCCFn fn, + void *params); + +void pwmDeinit( + EFR32PwmInstance *inst); + +void pwmOn( + EFR32PwmInstance *inst); + +void pwmOff( + EFR32PwmInstance *inst); + +void pwmStart( + EFR32PwmInstance *inst, + prevTimerInitFn fn, + void *params); + +void pwmDeadTimeInit( + EFR32PwmInstance *inst, + EFR32PwmDeadTimeConfig *config); + +#endif + +#endif \ No newline at end of file