Skip to content

Commit d32d1ce

Browse files
committed
Merge branch 'dev' of github.com:askuric/Arduino-FOC into dev
2 parents 3c7290b + a94c7dd commit d32d1ce

15 files changed

+334
-41
lines changed

.github/workflows/ccpp.yml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ jobs:
1616
- adafruit:samd:adafruit_metro_m4 # samd51
1717
- esp32:esp32:esp32doit-devkit-v1 # esp32
1818
- esp32:esp32:esp32s2 # esp32s2
19+
- esp32:esp32:esp32s3 # esp32s3
1920
- STMicroelectronics:stm32:GenF1:pnum=BLUEPILL_F103C8 # stm32 bluepill
2021
- STMicroelectronics:stm32:Nucleo_64:pnum=NUCLEO_F411RE # stm32 nucleo
2122
- STMicroelectronics:stm32:GenF4:pnum=GENERIC_F405RGTX # stm32f405 - odrive
@@ -51,6 +52,10 @@ jobs:
5152
platform-url: https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_dev_index.json
5253
sketch-names: bldc_driver_3pwm_standalone.ino, stepper_driver_2pwm_standalone.ino, stepper_driver_4pwm_standalone
5354

55+
- arduino-boards-fqbn: esp32:esp32:esp32s3 # esp32s3
56+
platform-url: https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_dev_index.json
57+
sketch-names: esp32_position_control.ino, esp32_i2c_dual_bus_example.ino
58+
5459
- arduino-boards-fqbn: esp32:esp32:esp32doit-devkit-v1 # esp32
5560
platform-url: https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_dev_index.json
5661
sketch-names: esp32_position_control.ino, esp32_i2c_dual_bus_example.ino, esp32_current_control_low_side.ino, esp32_spi_alt_example.ino

src/BLDCMotor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -345,7 +345,7 @@ void BLDCMotor::move(float new_target) {
345345
// when switching to a 2-component representation.
346346
if( controller!=MotionControlType::angle_openloop && controller!=MotionControlType::velocity_openloop )
347347
shaft_angle = shaftAngle(); // read value even if motor is disabled to keep the monitoring updated but not in openloop mode
348-
// get angular velocity
348+
// get angular velocity TODO the velocity reading probably also shouldn't happen in open loop modes?
349349
shaft_velocity = shaftVelocity(); // read value even if motor is disabled to keep the monitoring updated
350350

351351
// if disabled do nothing

src/communication/StepDirListener.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ void StepDirListener::init(){
1313
}
1414

1515
void StepDirListener::enableInterrupt(void (*doA)()){
16-
attachInterrupt(digitalPinToInterrupt(pin_step), doA, CHANGE);
16+
attachInterrupt(digitalPinToInterrupt(pin_step), doA, polarity);
1717
}
1818

1919
void StepDirListener::attach(float* variable){
@@ -22,15 +22,15 @@ void StepDirListener::attach(float* variable){
2222

2323
void StepDirListener::handle(){
2424
// read step status
25-
bool step = digitalRead(pin_step);
25+
//bool step = digitalRead(pin_step);
2626
// update counter only on rising edge
27-
if(step && step != step_active){
28-
if(digitalRead(pin_dir))
27+
//if(step && step != step_active){
28+
if(digitalRead(pin_dir))
2929
count++;
30-
else
30+
else
3131
count--;
32-
}
33-
step_active = step;
32+
//}
33+
//step_active = step;
3434
// if attached variable update it
3535
if(attached_variable) *attached_variable = getValue();
3636
}

src/communication/StepDirListener.h

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,12 @@
44
#include "Arduino.h"
55
#include "../common/foc_utils.h"
66

7+
8+
#if defined(_STM32_DEF_) || defined(ESP_H) || defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_SAM_DUE)
9+
#define PinStatus int
10+
#endif
11+
12+
713
/**
814
* Step/Dir listenner class for easier interraction with this communication interface.
915
*/
@@ -47,11 +53,13 @@ class StepDirListener
4753
int pin_step; //!< step pin
4854
int pin_dir; //!< direction pin
4955
long count; //!< current counter value - should be set to 0 for homing
56+
PinStatus polarity = RISING; //!< polarity of the step pin
5057

5158
private:
5259
float* attached_variable = nullptr; //!< pointer to the attached variable
5360
float counter_to_value; //!< step counter to value
54-
bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable
61+
//bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable
62+
5563
};
5664

5765
#endif

src/drivers/hardware_api.h

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,17 @@ typedef struct GenericDriverParams {
1919
float dead_zone;
2020
} GenericDriverParams;
2121

22+
/**
23+
* Configuring PWM frequency, resolution and alignment
24+
* - Stepper driver - 2PWM setting
25+
* - hardware specific
26+
*
27+
* @param pwm_frequency - frequency in hertz - if applicable
28+
* @param pinA pinA pwm pin
29+
*
30+
* @return -1 if failed, or pointer to internal driver parameters struct if successful
31+
*/
32+
void* _configure1PWM(long pwm_frequency, const int pinA);
2233

2334
/**
2435
* Configuring PWM frequency, resolution and alignment
@@ -80,6 +91,17 @@ void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const
8091
*/
8192
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);
8293

94+
/**
95+
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
96+
* - Stepper driver - 2PWM setting
97+
* - hardware specific
98+
*
99+
* @param dc_a duty cycle phase A [0, 1]
100+
* @param dc_b duty cycle phase B [0, 1]
101+
* @param params the driver parameters
102+
*/
103+
void _writeDutyCycle1PWM(float dc_a, void* params);
104+
83105
/**
84106
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
85107
* - Stepper driver - 2PWM setting

src/drivers/hardware_specific/atmega2560_mcu.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,21 @@ void _pinHighFrequency(const int pin){
2525
}
2626

2727

28+
// function setting the high pwm frequency to the supplied pins
29+
// - Stepper motor - 2PWM setting
30+
// - hardware speciffic
31+
void* _configure1PWM(long pwm_frequency,const int pinA) {
32+
// High PWM frequency
33+
// - always max 32kHz
34+
_pinHighFrequency(pinA);
35+
GenericDriverParams* params = new GenericDriverParams {
36+
.pins = { pinA },
37+
.pwm_frequency = pwm_frequency
38+
};
39+
return params;
40+
}
41+
42+
2843
// function setting the high pwm frequency to the supplied pins
2944
// - Stepper motor - 2PWM setting
3045
// - hardware speciffic
@@ -56,6 +71,14 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5671
return params;
5772
}
5873

74+
// function setting the pwm duty cycle to the hardware
75+
// - Stepper motor - 2PWM setting
76+
// - hardware speciffic
77+
void _writeDutyCycle1PWM(float dc_a, void* params){
78+
// transform duty cycle from [0,1] to [0,255]
79+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
80+
}
81+
5982
// function setting the pwm duty cycle to the hardware
6083
// - Stepper motor - 2PWM setting
6184
// - hardware speciffic

src/drivers/hardware_specific/atmega328_mcu.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,20 @@ void _pinHighFrequency(const int pin){
1717

1818
}
1919

20+
// function setting the high pwm frequency to the supplied pins
21+
// - Stepper motor - 2PWM setting
22+
// - hardware speciffic
23+
// supports Arudino/ATmega328
24+
void* _configure1PWM(long pwm_frequency,const int pinA) {
25+
// High PWM frequency
26+
// - always max 32kHz
27+
_pinHighFrequency(pinA);
28+
GenericDriverParams* params = new GenericDriverParams {
29+
.pins = { pinA },
30+
.pwm_frequency = pwm_frequency
31+
};
32+
return params;
33+
}
2034
// function setting the high pwm frequency to the supplied pins
2135
// - Stepper motor - 2PWM setting
2236
// - hardware speciffic
@@ -50,6 +64,18 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5064
return params;
5165
}
5266

67+
68+
69+
70+
// function setting the pwm duty cycle to the hardware
71+
// - Stepper motor - 2PWM setting
72+
// - hardware speciffic
73+
void _writeDutyCycle1PWM(float dc_a, void* params){
74+
// transform duty cycle from [0,1] to [0,255]
75+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
76+
}
77+
78+
5379
// function setting the pwm duty cycle to the hardware
5480
// - Stepper motor - 2PWM setting
5581
// - hardware speciffic

src/drivers/hardware_specific/atmega32u4_mcu.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,20 @@ void _pinHighFrequency(const int pin){
2828
}
2929

3030

31+
// function setting the high pwm frequency to the supplied pins
32+
// - Stepper motor - 2PWM setting
33+
// - hardware speciffic
34+
void* _configure1PWM(long pwm_frequency,const int pinA) {
35+
// High PWM frequency
36+
// - always max 32kHz
37+
_pinHighFrequency(pinA);
38+
GenericDriverParams* params = new GenericDriverParams {
39+
.pins = { pinA },
40+
.pwm_frequency = pwm_frequency
41+
};
42+
return params;
43+
}
44+
3145
// function setting the high pwm frequency to the supplied pins
3246
// - Stepper motor - 2PWM setting
3347
// - hardware speciffic
@@ -59,6 +73,17 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5973
return params;
6074
}
6175

76+
77+
78+
// function setting the pwm duty cycle to the hardware
79+
// - Stepper motor - 2PWM setting
80+
// - hardware speciffic
81+
void _writeDutyCycle1PWM(float dc_a, void* params){
82+
// transform duty cycle from [0,1] to [0,255]
83+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
84+
}
85+
86+
6287
// function setting the pwm duty cycle to the hardware
6388
// - Stepper motor - 2PWM setting
6489
// - hardware speciffic

src/drivers/hardware_specific/esp32_ledc_mcu.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,33 @@ void _setHighFrequency(const long freq, const int pin, const int channel){
5353

5454

5555

56+
57+
58+
59+
void* _configure1PWM(long pwm_frequency, const int pinA) {
60+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
61+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
62+
63+
// check if enough channels available
64+
if ( channel_index + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
65+
66+
int ch1 = channel_index++;
67+
_setHighFrequency(pwm_frequency, pinA, ch1);
68+
69+
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
70+
.channels = { ch1 },
71+
.pwm_frequency = pwm_frequency
72+
};
73+
return params;
74+
}
75+
76+
77+
78+
79+
80+
81+
82+
5683
void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
5784
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
5885
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
@@ -123,6 +150,12 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
123150

124151

125152

153+
void _writeDutyCycle1PWM(float dc_a, void* params){
154+
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
155+
}
156+
157+
158+
126159
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
127160
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
128161
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[1], _constrain(_PWM_RES*dc_b, 0, _PWM_RES));

src/drivers/hardware_specific/esp8266_mcu.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,22 @@ void _setHighFrequency(const long freq, const int pin){
1212
}
1313

1414

15+
// function setting the high pwm frequency to the supplied pins
16+
// - Stepper motor - 2PWM setting
17+
// - hardware speciffic
18+
void* _configure1PWM(long pwm_frequency, const int pinA) {
19+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
20+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
21+
_setHighFrequency(pwm_frequency, pinA);
22+
GenericDriverParams* params = new GenericDriverParams {
23+
.pins = { pinA },
24+
.pwm_frequency = pwm_frequency
25+
};
26+
return params;
27+
}
28+
29+
30+
1531
// function setting the high pwm frequency to the supplied pins
1632
// - Stepper motor - 2PWM setting
1733
// - hardware speciffic
@@ -60,6 +76,13 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
6076
return params;
6177
}
6278

79+
// function setting the pwm duty cycle to the hardware
80+
// - Stepper motor - 2PWM setting
81+
// - hardware speciffic
82+
void _writeDutyCycle1PWM(float dc_a, void* params){
83+
// transform duty cycle from [0,1] to [0,255]
84+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
85+
}
6386
// function setting the pwm duty cycle to the hardware
6487
// - Stepper motor - 2PWM setting
6588
// - hardware speciffic

src/drivers/hardware_specific/generic_mcu.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,18 @@
55
__attribute__((weak)) void analogWrite(uint8_t pin, int value){ };
66
#endif
77

8+
// function setting the high pwm frequency to the supplied pin
9+
// - Stepper motor - 1PWM setting
10+
// - hardware speciffic
11+
// in generic case dont do anything
12+
__attribute__((weak)) void* _configure1PWM(long pwm_frequency, const int pinA) {
13+
GenericDriverParams* params = new GenericDriverParams {
14+
.pins = { pinA },
15+
.pwm_frequency = pwm_frequency
16+
};
17+
return params;
18+
}
19+
820
// function setting the high pwm frequency to the supplied pins
921
// - Stepper motor - 2PWM setting
1022
// - hardware speciffic
@@ -59,6 +71,15 @@ __attribute__((weak)) void* _configure6PWM(long pwm_frequency, float dead_zone,
5971
}
6072

6173

74+
// function setting the pwm duty cycle to the hardware
75+
// - Stepper motor - 1PWM setting
76+
// - hardware speciffic
77+
__attribute__((weak)) void _writeDutyCycle1PWM(float dc_a, void* params){
78+
// transform duty cycle from [0,1] to [0,255]
79+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
80+
}
81+
82+
6283
// function setting the pwm duty cycle to the hardware
6384
// - Stepper motor - 2PWM setting
6485
// - hardware speciffic

0 commit comments

Comments
 (0)