Skip to content

Commit 74aacac

Browse files
committed
FEAT added stepper with 2pwm and esp32 refactoring
1 parent 906d40f commit 74aacac

File tree

12 files changed

+390
-29
lines changed

12 files changed

+390
-29
lines changed
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
// Stepper driver standalone example
2+
#include <SimpleFOC.h>
3+
4+
5+
// Stepper driver instance
6+
// StepperDriver2PWM(pwm1, in1a, in1b, pwm2, in2a, in2b, (en1, en2 optional))
7+
StepperDriver2PWM driver = StepperDriver2PWM(3, 4, 5, 10 , 9 , 8 , 11, 12);
8+
9+
void setup() {
10+
11+
// pwm frequency to be used [Hz]
12+
// for atmega328 fixed to 32kHz
13+
// esp32/stm32/teensy configurable
14+
driver.pwm_frequency = 30000;
15+
// power supply voltage [V]
16+
driver.voltage_power_supply = 12;
17+
// Max DC voltage allowed - default voltage_power_supply
18+
driver.voltage_limit = 12;
19+
20+
// driver init
21+
driver.init();
22+
23+
// enable driver
24+
driver.enable();
25+
26+
_delay(1000);
27+
}
28+
29+
void loop() {
30+
// setting pwm
31+
// phase A: 3V
32+
// phase B: 6V
33+
driver.setPwm(3,6);
34+
}

examples/utils/driver_standalone_test/stepper_driver_4pwm_standalone/stepper_driver_4pwm_standalone.ino

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,14 +3,15 @@
33

44

55
// Stepper driver instance
6+
// StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1, en2 optional))
67
StepperDriver4PWM driver = StepperDriver4PWM(5, 6, 9,10, 7, 8);
78

89
void setup() {
910

1011
// pwm frequency to be used [Hz]
1112
// for atmega328 fixed to 32kHz
1213
// esp32/stm32/teensy configurable
13-
driver.pwm_frequency = 50000;
14+
driver.pwm_frequency = 30000;
1415
// power supply voltage [V]
1516
driver.voltage_power_supply = 12;
1617
// Max DC voltage allowed - default voltage_power_supply

keywords.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ BLDCDriver3PWM KEYWORD1
1212
BLDCDriver6PWM KEYWORD1
1313
BLDCDriver KEYWORD1
1414
StepperDriver4PWM KEYWORD1
15+
StepperDriver2PWM KEYWORD1
1516
StepperDriver KEYWORD1
1617

1718
initFOC KEYWORD2

src/SimpleFOC.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,5 +106,6 @@ void loop() {
106106
#include "drivers/BLDCDriver3PWM.h"
107107
#include "drivers/BLDCDriver6PWM.h"
108108
#include "drivers/StepperDriver4PWM.h"
109+
#include "drivers/StepperDriver2PWM.h"
109110

110111
#endif

src/StepperMotor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -246,7 +246,7 @@ void StepperMotor::velocityOpenloop(float target_velocity){
246246

247247
// calculate the necessary angle to achieve target velocity
248248
shaft_angle += target_velocity*Ts;
249-
249+
250250
// set the maximal allowed voltage (voltage_limit) with the necessary angle
251251
setPhaseVoltage(voltage_limit, 0, _electricalAngle(shaft_angle,pole_pairs));
252252

src/drivers/StepperDriver2PWM.cpp

Lines changed: 96 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
#include "StepperDriver2PWM.h"
2+
3+
StepperDriver2PWM::StepperDriver2PWM(int ph1PWM, int ph1INA, int ph1INB, int ph2PWM, int ph2INA, int ph2INB, int en1, int en2){
4+
// Pin initialization
5+
pwm1 = ph1PWM; //!< phase 1 pwm pin number
6+
ina1 = ph1INA; //!< phase 1 INA pin number
7+
inb1 = ph1INB; //!< phase 1 INB pin number
8+
pwm2 = ph2PWM; //!< phase 2 pwm pin number
9+
ina2 = ph2INA; //!< phase 2 INA pin number
10+
inb2 = ph2INB; //!< phase 2 INB pin number
11+
12+
// enable_pin pin
13+
enable_pin1 = en1;
14+
enable_pin2 = en2;
15+
16+
// default power-supply value
17+
voltage_power_supply = DEF_POWER_SUPPLY;
18+
voltage_limit = NOT_SET;
19+
20+
}
21+
22+
// enable motor driver
23+
void StepperDriver2PWM::enable(){
24+
// enable_pin the driver - if enable_pin pin available
25+
if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, HIGH);
26+
if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, HIGH);
27+
// set zero to PWM
28+
setPwm(0,0);
29+
}
30+
31+
// disable motor driver
32+
void StepperDriver2PWM::disable()
33+
{
34+
// set zero to PWM
35+
setPwm(0, 0);
36+
// disable the driver - if enable_pin pin available
37+
if ( enable_pin1 != NOT_SET ) digitalWrite(enable_pin1, LOW);
38+
if ( enable_pin2 != NOT_SET ) digitalWrite(enable_pin2, LOW);
39+
40+
}
41+
42+
// init hardware pins
43+
int StepperDriver2PWM::init() {
44+
45+
// PWM pins
46+
pinMode(pwm1, OUTPUT);
47+
pinMode(pwm2, OUTPUT);
48+
pinMode(ina1, OUTPUT);
49+
pinMode(ina2, OUTPUT);
50+
pinMode(inb1, OUTPUT);
51+
pinMode(inb2, OUTPUT);
52+
53+
if(enable_pin1 != NOT_SET) pinMode(enable_pin1, OUTPUT);
54+
if(enable_pin2 != NOT_SET) pinMode(enable_pin2, OUTPUT);
55+
56+
// sanity check for the voltage limit configuration
57+
if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
58+
59+
// Set the pwm frequency to the pins
60+
// hardware specific function - depending on driver and mcu
61+
_configure2PWM(pwm_frequency, pwm1, pwm2);
62+
return 0;
63+
}
64+
65+
66+
// Set voltage to the pwm pin
67+
void StepperDriver2PWM::setPwm(float Ualpha, float Ubeta) {
68+
float duty_cycle1(0.0),duty_cycle2(0.0);
69+
// limit the voltage in driver
70+
Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit);
71+
Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit);
72+
// hardware specific writing
73+
duty_cycle1 = _constrain(abs(Ualpha)/voltage_power_supply,0.0,1.0);
74+
duty_cycle2 = _constrain(abs(Ubeta)/voltage_power_supply,0.0,1.0);
75+
// set direction
76+
if( Ualpha > 0 ){
77+
digitalWrite(inb1, LOW);
78+
digitalWrite(ina1, HIGH);
79+
}
80+
else{
81+
digitalWrite(ina1, LOW);
82+
digitalWrite(inb1, HIGH);
83+
}
84+
85+
if( Ubeta > 0 ){
86+
digitalWrite(ina2, LOW);
87+
digitalWrite(inb2, HIGH);
88+
}
89+
else{
90+
digitalWrite(inb2, LOW);
91+
digitalWrite(ina2, HIGH);
92+
}
93+
94+
// write to hardware
95+
_writeDutyCycle2PWM(duty_cycle1, duty_cycle2, pwm1, pwm2);
96+
}

src/drivers/StepperDriver2PWM.h

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
#ifndef STEPPER_DRIVER_2PWM_h
2+
#define STEPPER_DRIVER_2PWM_h
3+
4+
#include "../common/base_classes/StepperDriver.h"
5+
#include "../common/foc_utils.h"
6+
#include "../common/time_utils.h"
7+
#include "../common/defaults.h"
8+
#include "hardware_api.h"
9+
10+
/**
11+
2 pwm stepper driver class
12+
*/
13+
class StepperDriver2PWM: public StepperDriver
14+
{
15+
public:
16+
/**
17+
StepperMotor class constructor
18+
@param ph1PWM PWM1 phase pwm pin
19+
@param ph1INA IN1A phase dir pin
20+
@param ph1INB IN1B phase dir pin
21+
@param ph2PWM PWM2 phase pwm pin
22+
@param ph2INA IN2A phase dir pin
23+
@param ph2INB IN2B phase dir pin
24+
@param en1 enable pin phase 1 (optional input)
25+
@param en2 enable pin phase 2 (optional input)
26+
*/
27+
StepperDriver2PWM(int ph1PWM,int ph1INA,int ph1INB,int ph2PWM,int ph2INA,int ph2INB, int en1 = NOT_SET, int en2 = NOT_SET);
28+
29+
/** Motor hardware init function */
30+
int init() override;
31+
/** Motor disable function */
32+
void disable() override;
33+
/** Motor enable function */
34+
void enable() override;
35+
36+
// hardware variables
37+
int pwm1; //!< phase 1 pwm pin number
38+
int ina1; //!< phase 1 INA pin number
39+
int inb1; //!< phase 1 INB pin number
40+
int pwm2; //!< phase 2 pwm pin number
41+
int ina2; //!< phase 2 INA pin number
42+
int inb2; //!< phase 2 INB pin number
43+
int enable_pin1; //!< enable pin number phase 1
44+
int enable_pin2; //!< enable pin number phase 2
45+
46+
/**
47+
* Set phase voltages to the harware
48+
*
49+
* @param Ua phase A voltage
50+
* @param Ub phase B voltage
51+
*/
52+
void setPwm(float Ua, float Ub) override;
53+
54+
private:
55+
56+
};
57+
58+
59+
#endif

src/drivers/hardware_api.h

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,17 @@
44
#include "../common/foc_utils.h"
55
#include "../common/time_utils.h"
66

7+
/**
8+
* Configuring PWM frequency, resolution and alignment
9+
* - Stepper driver - 2PWM setting
10+
* - hardware specific
11+
*
12+
* @param pwm_frequency - frequency in hertz - if applicable
13+
* @param pinA pinA bldc driver
14+
* @param pinB pinB bldc driver
15+
*/
16+
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
17+
718
/**
819
* Configuring PWM frequency, resolution and alignment
920
* - BLDC driver - 3PWM setting
@@ -47,6 +58,18 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const
4758
*/
4859
int _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);
4960

61+
/**
62+
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
63+
* - Stepper driver - 2PWM setting
64+
* - hardware specific
65+
*
66+
* @param dc_a duty cycle phase A [0, 1]
67+
* @param dc_b duty cycle phase B [0, 1]
68+
* @param pinA phase A hardware pin number
69+
* @param pinB phase B hardware pin number
70+
*/
71+
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB);
72+
5073
/**
5174
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
5275
* - BLDC driver - 3PWM setting

src/drivers/hardware_specific/atmega328_mcu.cpp

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

1818
}
1919

20+
21+
// function setting the high pwm frequency to the supplied pins
22+
// - Stepper motor - 2PWM setting
23+
// - hardware speciffic
24+
// supports Arudino/ATmega328
25+
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
26+
// High PWM frequency
27+
// - always max 32kHz
28+
_pinHighFrequency(pinA);
29+
_pinHighFrequency(pinB);
30+
}
31+
2032
// function setting the high pwm frequency to the supplied pins
2133
// - BLDC motor - 3PWM setting
2234
// - hardware speciffic
@@ -29,6 +41,14 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
2941
_pinHighFrequency(pinC);
3042
}
3143

44+
// function setting the pwm duty cycle to the hardware
45+
// - Stepper motor - 2PWM setting
46+
// - hardware speciffic
47+
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
48+
// transform duty cycle from [0,1] to [0,255]
49+
analogWrite(pinA, 255.0*dc_a);
50+
analogWrite(pinB, 255.0*dc_b);
51+
}
3252

3353
// function setting the pwm duty cycle to the hardware
3454
// - BLDC motor - 3PWM setting

0 commit comments

Comments
 (0)