Skip to content

Commit fa590e6

Browse files
committed
teensy 4 6pwm added
1 parent 86aa4b8 commit fa590e6

File tree

34 files changed

+642
-47
lines changed

34 files changed

+642
-47
lines changed

.github/workflows/ccpp.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ jobs:
2727
- arduino-boards-fqbn: arduino:avr:uno # arudino uno - compiling almost all examples
2828
sketch-names: '**.ino'
2929
required-libraries: PciManager
30-
sketches-exclude: 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
30+
sketches-exclude: 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
3131

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

README.md

Lines changed: 3 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -24,30 +24,9 @@ Therefore this is an attempt to:
2424
- *Medium-power* BLDC driver (<30Amps): [Arduino <span class="simple">Simple<b>FOC</b>PowerShield</span> ](https://github.com/simplefoc/Arduino-SimpleFOC-PowerShield).
2525
- See also [@byDagor](https://github.com/byDagor)'s *fully-integrated* ESP32 based board: [Dagor Brushless Controller](https://github.com/byDagor/Dagor-Brushless-Controller)
2626

27-
> NEW RELEASE 📢 : <span class="simple">Simple<span class="foc">FOC</span>library</span> v2.2.3
28-
> - stm32 low-side current sensing
29-
> - g4 supported
30-
> - thoroughly tested f1/f4/g4 - [#187](https://github.com/simplefoc/Arduino-FOC/issues/187)
31-
> - bg431b: added support for VBAT and TEMPERATURE readings [#222](https://github.com/simplefoc/Arduino-FOC/pull/222)
32-
> - bugfixing
33-
> - leonardo
34-
> - mega2560 [#190](https://github.com/simplefoc/Arduino-FOC/issues/190)
35-
> - inline current sense without driver [#188](https://github.com/simplefoc/Arduino-FOC/issues/188)
36-
> - bg431b support current sense fix [#210](https://github.com/simplefoc/Arduino-FOC/pull/210)
37-
> - StepperDriver4PWM wrong init [#182](https://github.com/simplefoc/Arduino-FOC/issues/182)
38-
> - open loop back-emf vlotage issue [#219](https://github.com/simplefoc/Arduino-FOC/issues/219)
39-
> - SAMD51 compile issue [#217](https://github.com/simplefoc/Arduino-FOC/issues/217)
40-
> - ESP32-S3 compile issue [#198](https://github.com/simplefoc/Arduino-FOC/issues/198)
41-
> - ESP32 compile issue [#208](https://github.com/simplefoc/Arduino-FOC/issues/208), [#207](https://github.com/simplefoc/Arduino-FOC/issues/207)
42-
> - magnetic sensor direction finding more robust [#173](https://github.com/simplefoc/Arduino-FOC/issues/173), [#164](https://github.com/simplefoc/Arduino-FOC/pull/164)
43-
> - `StepDirListener` improved timing [#169](https://github.com/simplefoc/Arduino-FOC/issues/169), [#209](https://github.com/simplefoc/Arduino-FOC/pull/209)
44-
> - API changes
45-
> - `setPhaseVoltage` is now public function
46-
> - `getVelocity` can now be called as many times as necessary (it recalculates the velocity if the time between calls is longer then `min_elapsed_time` - default 0.1ms)
47-
> - BG431 board can be used only with `LowsideCurrentSense` class!
48-
> - `initFOC` fails if current sense not initialised
49-
> - driver and curent sense have to be well initialised for `initFOC` to start
50-
> - `cs.init()` and `driver.init()` return `1` if well initialised and `0` if failed
27+
> NEXT RELEASE 📢 : <span class="simple">Simple<span class="foc">FOC</span>library</span> v2.3.0
28+
> - Teensy 3.x inital support for 6pwm
29+
> - Teensy 4.x inital support for 6pwm
5130
## Arduino *SimpleFOClibrary* v2.2.3
5231

5332
<p align="">
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
// 6pwm openloop velocity example
2+
#include <SimpleFOC.h>
3+
4+
5+
// BLDC motor & driver instance
6+
// BLDCMotor motor = BLDCMotor(pole pair number);
7+
BLDCMotor motor = BLDCMotor(11);
8+
// using FTM0 timer
9+
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
10+
BLDCDriver6PWM driver = BLDCDriver6PWM(22,23, 9,10, 6,20, 8);
11+
// using FTM3 timer - available on Teensy3.5 and Teensy3.6
12+
// BLDCDriver6PWM driver = BLDCDriver6PWM(2,14, 7,8, 35,36, 8);
13+
14+
// instantiate the commander
15+
Commander command = Commander(Serial);
16+
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
17+
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
18+
19+
void setup() {
20+
21+
// driver config
22+
// power supply voltage [V]
23+
driver.voltage_power_supply = 12;
24+
// limit the maximal dc voltage the driver can set
25+
// as a protection measure for the low-resistance motors
26+
// this value is fixed on startup
27+
driver.voltage_limit = 6;
28+
driver.init();
29+
// link the motor and the driver
30+
motor.linkDriver(&driver);
31+
32+
// limiting motor movements
33+
// limit the voltage to be set to the motor
34+
// start very low for high resistance motors
35+
// currnet = resistance*voltage, so try to be well under 1Amp
36+
motor.voltage_limit = 3; // [V]
37+
38+
// open loop control config
39+
motor.controller = MotionControlType::velocity_openloop;
40+
41+
// init motor hardware
42+
motor.init();
43+
44+
//initial motor target
45+
motor.target=0;
46+
47+
// add target command T
48+
command.add('T', doTarget, "target velocity");
49+
command.add('L', doLimit, "voltage limit");
50+
51+
Serial.begin(115200);
52+
Serial.println("Motor ready!");
53+
Serial.println("Set target velocity [rad/s]");
54+
_delay(1000);
55+
}
56+
57+
void loop() {
58+
59+
// open loop velocity movement
60+
// using motor.voltage_limit
61+
motor.move();
62+
63+
// user communication
64+
command.run();
65+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
// 6pwm standalone example code for Teensy 4.x boards
2+
//
3+
// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
4+
// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
5+
//
6+
// List of available teensy 4.1 pins with their respective submodules and channels
7+
// FlexPWM(timer number)_(submodule)_(channel)
8+
// FlexPWM4_2_A pin 2
9+
// FlexPWM4_2_B pin 3
10+
// FlexPWM1_3_B pin 7
11+
// FlexPWM1_3_A pin 8
12+
// FlexPWM2_2_A pin 6
13+
// FlexPWM2_2_B pin 9
14+
// FlexPWM3_1_B pin 28
15+
// FlexPWM3_1_A pin 29
16+
// FlexPWM2_3_A pin 36
17+
// FlexPWM2_3_B pin 37
18+
#include <SimpleFOC.h>
19+
20+
21+
// BLDC driver instance
22+
// make sure to provide channel A for high side and channel B for low side
23+
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
24+
// Example configuration
25+
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
26+
27+
void setup() {
28+
// pwm frequency to be used [Hz]
29+
driver.pwm_frequency = 30000;
30+
// dead zone percentage of the duty cycle - default 0.02 - 2%
31+
driver.dead_zone=0.02;
32+
// power supply voltage [V]
33+
driver.voltage_power_supply = 12;
34+
// Max DC voltage allowed - default voltage_power_supply
35+
driver.voltage_limit = 12;
36+
37+
// driver init
38+
driver.init();
39+
40+
// enable driver
41+
driver.enable();
42+
43+
_delay(1000);
44+
}
45+
46+
void loop() {
47+
// setting pwm
48+
// phase A: 3V
49+
// phase B: 6V
50+
// phase C: 5V
51+
driver.setPwm(3,6,5);
52+
}
Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,80 @@
1+
// 6pwm openloop velocity example
2+
//
3+
// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
4+
// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
5+
//
6+
// List of available teensy 4.1 pins with their respective submodules and channels
7+
// FlexPWM(timer number)_(submodule)_(channel)
8+
// FlexPWM4_2_A pin 2
9+
// FlexPWM4_2_B pin 3
10+
// FlexPWM1_3_B pin 7
11+
// FlexPWM1_3_A pin 8
12+
// FlexPWM2_2_A pin 6
13+
// FlexPWM2_2_B pin 9
14+
// FlexPWM3_1_B pin 28
15+
// FlexPWM3_1_A pin 29
16+
// FlexPWM2_3_A pin 36
17+
// FlexPWM2_3_B pin 37
18+
#include <SimpleFOC.h>
19+
20+
21+
// BLDC motor & driver instance
22+
// BLDCMotor motor = BLDCMotor(pole pair number);
23+
BLDCMotor motor = BLDCMotor(11);
24+
// make sure to provide channel A for high side and channel B for low side
25+
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
26+
// Example configuration
27+
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
28+
29+
// instantiate the commander
30+
Commander command = Commander(Serial);
31+
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
32+
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
33+
34+
void setup() {
35+
36+
// driver config
37+
// power supply voltage [V]
38+
driver.voltage_power_supply = 12;
39+
// limit the maximal dc voltage the driver can set
40+
// as a protection measure for the low-resistance motors
41+
// this value is fixed on startup
42+
driver.voltage_limit = 6;
43+
driver.init();
44+
// link the motor and the driver
45+
motor.linkDriver(&driver);
46+
47+
// limiting motor movements
48+
// limit the voltage to be set to the motor
49+
// start very low for high resistance motors
50+
// currnet = resistance*voltage, so try to be well under 1Amp
51+
motor.voltage_limit = 3; // [V]
52+
53+
// open loop control config
54+
motor.controller = MotionControlType::velocity_openloop;
55+
56+
// init motor hardware
57+
motor.init();
58+
59+
//initial motor target
60+
motor.target=0;
61+
62+
// add target command T
63+
command.add('T', doTarget, "target velocity");
64+
command.add('L', doLimit, "voltage limit");
65+
66+
Serial.begin(115200);
67+
Serial.println("Motor ready!");
68+
Serial.println("Set target velocity [rad/s]");
69+
_delay(1000);
70+
}
71+
72+
void loop() {
73+
74+
// open loop velocity movement
75+
// using motor.voltage_limit
76+
motor.move();
77+
78+
// user communication
79+
command.run();
80+
}

src/current_sense/hardware_specific/esp32/esp32_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include "../../hardware_api.h"
22
#include "../../../drivers/hardware_api.h"
3-
#include "../../../drivers/hardware_specific/esp32_driver_mcpwm.h"
3+
#include "../../../drivers/hardware_specific/esp32/esp32_driver_mcpwm.h"
44

55
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
66

src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
#include "b_g431_hal.h"
66
#include "Arduino.h"
77
#include "../stm32_mcu.h"
8-
#include "../../../../drivers/hardware_specific/stm32_mcu.h"
8+
#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
99
#include "communication/SimpleFOCDebug.h"
1010

1111
#define _ADC_VOLTAGE 3.3f

src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
#if defined(STM32F1xx)
77
#include "stm32f1xx_hal.h"
88
#include "../../../../common/foc_utils.h"
9-
#include "../../../../drivers/hardware_specific/stm32_mcu.h"
9+
#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
1010
#include "../stm32_mcu.h"
1111

1212
int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);

src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
#if defined(STM32F1xx)
44
#include "../../../../common/foc_utils.h"
55
#include "../../../../drivers/hardware_api.h"
6-
#include "../../../../drivers/hardware_specific/stm32_mcu.h"
6+
#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
77
#include "../../../hardware_api.h"
88
#include "../stm32_mcu.h"
99
#include "stm32f1_hal.h"

0 commit comments

Comments
 (0)