SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
esp8266_mcu.cpp
Go to the documentation of this file.
1#include "../hardware_api.h"
2
3#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP8266)
4
5
6#pragma message("")
7#pragma message("SimpleFOC: compiling for ESP8266")
8#pragma message("")
9
10
11#define _PWM_FREQUENCY 25000 // 25khz
12#define _PWM_FREQUENCY_MAX 50000 // 50khz
13
14// configure High PWM frequency
15void _setHighFrequency(const long freq, const int pin){
16 analogWrite(pin, 0);
17 analogWriteFreq(freq);
18}
19
20
21// function setting the high pwm frequency to the supplied pins
22// - Stepper motor - 2PWM setting
23// - hardware speciffic
24void* _configure1PWM(long pwm_frequency, const int pinA) {
25 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
26 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
27 _setHighFrequency(pwm_frequency, pinA);
29 .pins = { pinA },
30 .pwm_frequency = pwm_frequency
31 };
32 return params;
33}
34
35
36
37// function setting the high pwm frequency to the supplied pins
38// - Stepper motor - 2PWM setting
39// - hardware speciffic
40void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
41 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
42 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
43 _setHighFrequency(pwm_frequency, pinA);
44 _setHighFrequency(pwm_frequency, pinB);
46 .pins = { pinA, pinB },
47 .pwm_frequency = pwm_frequency
48 };
49 return params;
50}
51
52// function setting the high pwm frequency to the supplied pins
53// - BLDC motor - 3PWM setting
54// - hardware speciffic
55void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
56 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
57 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
58 _setHighFrequency(pwm_frequency, pinA);
59 _setHighFrequency(pwm_frequency, pinB);
60 _setHighFrequency(pwm_frequency, pinC);
62 .pins = { pinA, pinB, pinC },
63 .pwm_frequency = pwm_frequency
64 };
65 return params;
66}
67
68// function setting the high pwm frequency to the supplied pins
69// - Stepper motor - 4PWM setting
70// - hardware speciffic
71void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
72 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
73 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
74 _setHighFrequency(pwm_frequency, pinA);
75 _setHighFrequency(pwm_frequency, pinB);
76 _setHighFrequency(pwm_frequency, pinC);
77 _setHighFrequency(pwm_frequency, pinD);
79 .pins = { pinA, pinB, pinC, pinD },
80 .pwm_frequency = pwm_frequency
81 };
82 return params;
83}
84
85// function setting the pwm duty cycle to the hardware
86// - Stepper motor - 2PWM setting
87// - hardware speciffic
88void _writeDutyCycle1PWM(float dc_a, void* params){
89 // transform duty cycle from [0,1] to [0,255]
90 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
91}
92// function setting the pwm duty cycle to the hardware
93// - Stepper motor - 2PWM setting
94// - hardware speciffic
95void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
96 // transform duty cycle from [0,1] to [0,255]
97 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
98 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
99}
100// function setting the pwm duty cycle to the hardware
101// - BLDC motor - 3PWM setting
102// - hardware speciffic
103void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
104 // transform duty cycle from [0,1] to [0,255]
105 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
106 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
107 analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
108}
109
110// function setting the pwm duty cycle to the hardware
111// - Stepper motor - 4PWM setting
112// - hardware speciffic
113void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
114 // transform duty cycle from [0,1] to [0,255]
115 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
116 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
117 analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
118 analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
119}
120
121#endif
const int const int const int pinC
GenericCurrentSenseParams * params
void * _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
void * _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
void _writeDutyCycle2PWM(float dc_a, float dc_b, void *params)
void _writeDutyCycle1PWM(float dc_a, void *params)
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void *params)
void * _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
void * _configure1PWM(long pwm_frequency, const int pinA)
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void *params)
float float float dc_2b
analogWrite(((GenericDriverParams *) params) ->pins[1], 255.0f *dc_b)
#define _isset(a)
Definition foc_utils.h:13
#define _constrain(amt, low, high)
Definition foc_utils.h:11