Skip to content

Commit dbececd

Browse files
committed
esp32s2/s3 support for multiple motors + cs separation
1 parent a3d72c0 commit dbececd

File tree

7 files changed

+240
-77
lines changed

7 files changed

+240
-77
lines changed

src/current_sense/hardware_specific/esp32_adc_driver.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include "esp32_adc_driver.h"
22

3-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
3+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
44

55
#include "freertos/FreeRTOS.h"
66
#include "freertos/task.h"

src/current_sense/hardware_specific/esp32_adc_driver.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55

66
#include "Arduino.h"
77

8-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
8+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
99
/*
1010
* Get ADC value for pin
1111
* */
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
#include "../hardware_api.h"
2+
#include "../../drivers/hardware_api.h"
3+
4+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && !defined(SOC_MCPWM_SUPPORTED)
5+
6+
#define _ADC_VOLTAGE 3.3f
7+
#define _ADC_RESOLUTION 4095.0f
8+
9+
// adc counts to voltage conversion ratio
10+
// some optimizing for faster execution
11+
#define _ADC_CONV ( (_ADC_VOLTAGE) / (_ADC_RESOLUTION) )
12+
13+
14+
/**
15+
* Inline adc reading implementation
16+
*/
17+
// function reading an ADC value and returning the read voltage
18+
float _readADCVoltageInline(const int pinA){
19+
uint32_t raw_adc = analogRead(pinA);
20+
// uint32_t raw_adc = analogRead(pinA);
21+
return raw_adc * _ADC_CONV;
22+
}
23+
24+
// function reading an ADC value and returning the read voltage
25+
void _configureADCInline(const int pinA,const int pinB, const int pinC){
26+
pinMode(pinA, INPUT);
27+
pinMode(pinB, INPUT);
28+
if( _isset(pinC) ) pinMode(pinC, INPUT);
29+
}
30+
#endif

src/current_sense/hardware_specific/esp32_mcu.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,9 @@
11
#include "../hardware_api.h"
22
#include "../../drivers/hardware_api.h"
33

4-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
4+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
5+
6+
#include "esp32_adc_driver.h"
57

68
#include "driver/mcpwm.h"
79
#include "soc/mcpwm_reg.h"
@@ -10,8 +12,6 @@
1012
#include <soc/sens_reg.h>
1113
#include <soc/sens_struct.h>
1214

13-
#include "esp32_adc_driver.h"
14-
1515
#define _ADC_VOLTAGE 3.3f
1616
#define _ADC_RESOLUTION 4095.0f
1717

@@ -121,5 +121,4 @@ static void IRAM_ATTR isr_handler(void*){
121121
if( _isset(_pinC) ) MCPWM[MCPWM_UNIT_0]->int_clr.timer2_tep_int_clr = mcpwm_intr_status_2;
122122
}
123123

124-
125124
#endif
Lines changed: 204 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,204 @@
1+
#include "../hardware_api.h"
2+
3+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)// && !defined(SOC_MCPWM_SUPPORTED)
4+
5+
#include "driver/ledc.h"
6+
7+
#define _PWM_FREQUENCY 25000 // 25khz
8+
#define _PWM_FREQUENCY_MAX 38000 // 38khz max to be able to have 10 bit pwm resolution
9+
#define _PWM_RES_BIT 10 // 10 bir resolution
10+
#define _PWM_RES 1023 // 2^10-1 = 1023-1
11+
12+
13+
// empty motor slot
14+
#define _EMPTY_SLOT -20
15+
#define _TAKEN_SLOT -21
16+
17+
// figure out how many ledc channels are avaible
18+
// esp32 - 2x8=16
19+
// esp32s2 - 8
20+
// esp32c3 - 6
21+
#include "soc/soc_caps.h"
22+
#ifdef SOC_LEDC_SUPPORT_HS_MODE
23+
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
24+
#else
25+
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
26+
#endif
27+
28+
// current channel stack index
29+
// support for multiple motors
30+
// esp32 has 16 channels
31+
// esp32s2 has 8 channels
32+
// esp32c3 has 6 channels
33+
int channel_index = 0;
34+
35+
// slot for the 3pwm bldc motors
36+
typedef struct {
37+
int pinID;
38+
int ch1;
39+
int ch2;
40+
int ch3;
41+
} bldc_3pwm_motor_slots_t;
42+
43+
// slot for the 2pwm stepper motors
44+
typedef struct {
45+
int pinID;
46+
int ch1;
47+
int ch2;
48+
} stepper_2pwm_motor_slots_t;
49+
50+
// slot for the 4pwm stepper motors
51+
typedef struct {
52+
int pinID;
53+
int ch1;
54+
int ch2;
55+
int ch3;
56+
int ch4;
57+
} stepper_4pwm_motor_slots_t;
58+
59+
60+
// define motor slots array
61+
bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = {
62+
{_EMPTY_SLOT, 0,0,0}, // 1st motor
63+
{_EMPTY_SLOT, 0,0,0}, // 2nd motor
64+
{_EMPTY_SLOT, 0,0,0}, // 3st motor // esp32s2 & esp32
65+
{_EMPTY_SLOT, 0,0,0}, // 4nd motor // esp32 only
66+
};
67+
stepper_2pwm_motor_slots_t esp32_stepper_2pwm_motor_slots[4]={
68+
{_EMPTY_SLOT, 0,0}, // 1st motor
69+
{_EMPTY_SLOT, 0,0}, // 2nd motor
70+
{_EMPTY_SLOT, 0,0}, // 3rd motor
71+
{_EMPTY_SLOT, 0,0} // 4th motor - esp32s2 and esp32
72+
};
73+
stepper_4pwm_motor_slots_t esp32_stepper_4pwm_motor_slots[4]={
74+
{_EMPTY_SLOT, 0,0,0,0}, // 1st motor
75+
{_EMPTY_SLOT, 0,0,0,0}, // 2nd motor - esp32s2 and esp32
76+
{_EMPTY_SLOT, 0,0,0,0}, // 3st motor - only esp32
77+
{_EMPTY_SLOT, 0,0,0,0}, // 4st motor - only esp32
78+
};
79+
80+
// configure High PWM frequency
81+
void _setHighFrequency(const long freq, const int pin, const int channel){
82+
ledcSetup(channel, freq, _PWM_RES_BIT );
83+
ledcAttachPin(pin, channel);
84+
}
85+
86+
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
87+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
88+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
89+
90+
// check if enough channels available
91+
if ( channel_index + 2 >= LEDC_CHANNELS ) return;
92+
93+
stepper_2pwm_motor_slots_t m_slot = {};
94+
95+
// determine which motor are we connecting
96+
// and set the appropriate configuration parameters
97+
for(int slot_num = 0; slot_num < 4; slot_num++){
98+
if(esp32_stepper_2pwm_motor_slots[slot_num].pinID == _EMPTY_SLOT){ // put the new motor in the first empty slot
99+
esp32_stepper_2pwm_motor_slots[slot_num].pinID = pinA;
100+
esp32_stepper_2pwm_motor_slots[slot_num].ch1 = channel_index++;
101+
esp32_stepper_2pwm_motor_slots[slot_num].ch2 = channel_index++;
102+
m_slot = esp32_stepper_2pwm_motor_slots[slot_num];
103+
break;
104+
}
105+
}
106+
107+
_setHighFrequency(pwm_frequency, pinA, m_slot.ch1);
108+
_setHighFrequency(pwm_frequency, pinB, m_slot.ch2);
109+
}
110+
111+
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
112+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
113+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
114+
115+
// check if enough channels available
116+
if ( channel_index + 3 >= LEDC_CHANNELS ) return;
117+
118+
bldc_3pwm_motor_slots_t m_slot = {};
119+
120+
// determine which motor are we connecting
121+
// and set the appropriate configuration parameters
122+
for(int slot_num = 0; slot_num < 4; slot_num++){
123+
if(esp32_bldc_3pwm_motor_slots[slot_num].pinID == _EMPTY_SLOT){ // put the new motor in the first empty slot
124+
esp32_bldc_3pwm_motor_slots[slot_num].pinID = pinA;
125+
esp32_bldc_3pwm_motor_slots[slot_num].ch1 = channel_index++;
126+
esp32_bldc_3pwm_motor_slots[slot_num].ch2 = channel_index++;
127+
esp32_bldc_3pwm_motor_slots[slot_num].ch3 = channel_index++;
128+
m_slot = esp32_bldc_3pwm_motor_slots[slot_num];
129+
break;
130+
}
131+
}
132+
133+
_setHighFrequency(pwm_frequency, pinA, m_slot.ch1);
134+
_setHighFrequency(pwm_frequency, pinB, m_slot.ch2);
135+
_setHighFrequency(pwm_frequency, pinC, m_slot.ch3);
136+
}
137+
138+
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
139+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
140+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
141+
142+
// check if enough channels available
143+
if ( channel_index + 4 >= LEDC_CHANNELS ) return;
144+
145+
146+
stepper_4pwm_motor_slots_t m_slot = {};
147+
148+
// determine which motor are we connecting
149+
// and set the appropriate configuration parameters
150+
for(int slot_num = 0; slot_num < 4; slot_num++){
151+
if(esp32_stepper_4pwm_motor_slots[slot_num].pinID == _EMPTY_SLOT){ // put the new motor in the first empty slot
152+
esp32_stepper_4pwm_motor_slots[slot_num].pinID = pinA;
153+
esp32_stepper_4pwm_motor_slots[slot_num].ch1 = channel_index++;
154+
esp32_stepper_4pwm_motor_slots[slot_num].ch2 = channel_index++;
155+
esp32_stepper_4pwm_motor_slots[slot_num].ch3 = channel_index++;
156+
esp32_stepper_4pwm_motor_slots[slot_num].ch4 = channel_index++;
157+
m_slot = esp32_stepper_4pwm_motor_slots[slot_num];
158+
break;
159+
}
160+
}
161+
162+
_setHighFrequency(pwm_frequency, pinA, m_slot.ch1);
163+
_setHighFrequency(pwm_frequency, pinB, m_slot.ch2);
164+
_setHighFrequency(pwm_frequency, pinC, m_slot.ch3);
165+
_setHighFrequency(pwm_frequency, pinD, m_slot.ch4);
166+
}
167+
168+
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
169+
// determine which motor slot is the motor connected to
170+
for(int i = 0; i < 4; i++){
171+
if(esp32_stepper_2pwm_motor_slots[i].pinID == pinA){ // if motor slot found
172+
ledcWrite(esp32_stepper_2pwm_motor_slots[i].ch1, _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
173+
ledcWrite(esp32_stepper_2pwm_motor_slots[i].ch2, _constrain(_PWM_RES*dc_b, 0, _PWM_RES));
174+
break;
175+
}
176+
}
177+
}
178+
179+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
180+
// determine which motor slot is the motor connected to
181+
for(int i = 0; i < 4; i++){
182+
if(esp32_bldc_3pwm_motor_slots[i].pinID == pinA){ // if motor slot found
183+
ledcWrite(esp32_bldc_3pwm_motor_slots[i].ch1, _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
184+
ledcWrite(esp32_bldc_3pwm_motor_slots[i].ch2, _constrain(_PWM_RES*dc_b, 0, _PWM_RES));
185+
ledcWrite(esp32_bldc_3pwm_motor_slots[i].ch3, _constrain(_PWM_RES*dc_c, 0, _PWM_RES));
186+
break;
187+
}
188+
}
189+
}
190+
191+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
192+
// determine which motor slot is the motor connected to
193+
for(int i = 0; i < 4; i++){
194+
if(esp32_stepper_4pwm_motor_slots[i].pinID == pin1A){ // if motor slot found
195+
ledcWrite(esp32_stepper_4pwm_motor_slots[i].ch1, _constrain(_PWM_RES*dc_1a, 0, _PWM_RES));
196+
ledcWrite(esp32_stepper_4pwm_motor_slots[i].ch2, _constrain(_PWM_RES*dc_1b, 0, _PWM_RES));
197+
ledcWrite(esp32_stepper_4pwm_motor_slots[i].ch3, _constrain(_PWM_RES*dc_2a, 0, _PWM_RES));
198+
ledcWrite(esp32_stepper_4pwm_motor_slots[i].ch4, _constrain(_PWM_RES*dc_2b, 0, _PWM_RES));
199+
break;
200+
}
201+
}
202+
}
203+
204+
#endif

src/drivers/hardware_specific/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

3-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
3+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && 0
44

55
#include "driver/mcpwm.h"
66
#include "soc/mcpwm_reg.h"

src/drivers/hardware_specific/esp32_nomcpwm.cpp

Lines changed: 0 additions & 70 deletions
This file was deleted.

0 commit comments

Comments
 (0)