Skip to content

Commit e628c61

Browse files
committed
FEAT updated to the version 1.4.1. - recolved memory issues + support for esp32
1 parent 82a365a commit e628c61

File tree

9 files changed

+474
-339
lines changed

9 files changed

+474
-339
lines changed

arduino_foc_minimal_encoder/BLDCMotor.cpp

Lines changed: 51 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -60,26 +60,24 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
6060

6161
// init hardware pins
6262
void BLDCMotor::init() {
63-
if(monitor_port) monitor_port->println("MONITOR: Initialize the motor pins.");
63+
if(monitor_port) monitor_port->println("MOT: Init pins.");
6464
// PWM pins
6565
pinMode(pwmA, OUTPUT);
6666
pinMode(pwmB, OUTPUT);
6767
pinMode(pwmC, OUTPUT);
6868
if(hasEnable()) pinMode(enable_pin, OUTPUT);
6969

70-
if(monitor_port) monitor_port->println("MONITOR: Set high frequency PWM.");
70+
if(monitor_port) monitor_port->println("MOT: PWM config.");
7171
// Increase PWM frequency to 32 kHz
7272
// make silent
73-
_setPwmFrequency(pwmA);
74-
_setPwmFrequency(pwmB);
75-
_setPwmFrequency(pwmC);
73+
_setPwmFrequency(pwmA, pwmB, pwmC);
7674

7775
// sanity check for the voltage limit configuration
7876
if(PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply;
7977

8078
_delay(500);
8179
// enable motor
82-
if(monitor_port) monitor_port->println("MONITOR: Enabling motor.");
80+
if(monitor_port) monitor_port->println("MOT: Enable.");
8381
enable();
8482
_delay(500);
8583

@@ -92,17 +90,13 @@ void BLDCMotor::disable()
9290
// disable the driver - if enable_pin pin available
9391
if (hasEnable()) digitalWrite(enable_pin, LOW);
9492
// set zero to PWM
95-
setPwm(pwmA, 0);
96-
setPwm(pwmB, 0);
97-
setPwm(pwmC, 0);
93+
setPwm(0, 0, 0);
9894
}
9995
// enable motor driver
10096
void BLDCMotor::enable()
10197
{
10298
// set zero to PWM
103-
setPwm(pwmA, 0);
104-
setPwm(pwmB, 0);
105-
setPwm(pwmC, 0);
99+
setPwm(0, 0, 0);
106100
// enable_pin the driver - if enable_pin pin available
107101
if (hasEnable()) digitalWrite(enable_pin, HIGH);
108102

@@ -115,7 +109,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) {
115109

116110
// Encoder alignment to electrical 0 angle
117111
int BLDCMotor::alignSensor() {
118-
if(monitor_port) monitor_port->println("MONITOR: Align the sensor's and motor electrical 0 angle.");
112+
if(monitor_port) monitor_port->println("MOT: Align sensor.");
119113
// align the electrical phases of the motor and sensor
120114
// set angle -90 degrees
121115
setPhaseVoltage(voltage_sensor_align, _3PI_2);
@@ -131,9 +125,9 @@ int BLDCMotor::alignSensor() {
131125
int exit_flag = absoluteZeroAlign();
132126
_delay(500);
133127
if(monitor_port){
134-
if(exit_flag< 0 ) monitor_port->println("MONITOR: Error: Absolute zero not found!");
135-
if(exit_flag> 0 ) monitor_port->println("MONITOR: Success: Absolute zero found!");
136-
else monitor_port->println("MONITOR: Absolute zero not available!");
128+
if(exit_flag< 0 ) monitor_port->println("MOT: Error: Not found!");
129+
if(exit_flag> 0 ) monitor_port->println("MOT: Success!");
130+
else monitor_port->println("MOT: Not available!");
137131
}
138132
return exit_flag;
139133
}
@@ -142,12 +136,13 @@ int BLDCMotor::alignSensor() {
142136
// Encoder alignment the absolute zero angle
143137
// - to the index
144138
int BLDCMotor::absoluteZeroAlign() {
145-
// if no absolute zero return
139+
140+
if(monitor_port) monitor_port->println("MOT: Absolute zero align.");
141+
// if no absolute zero return
146142
if(!sensor->hasAbsoluteZero()) return 0;
147143

148-
if(monitor_port) monitor_port->println("MONITOR: Aligning the absolute zero.");
149144

150-
if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MONITOR: Searching for absolute zero.");
145+
if(monitor_port && sensor->needsAbsoluteZeroSearch()) monitor_port->println("MOT: Searching...");
151146
// search the absolute zero with small velocity
152147
while(sensor->needsAbsoluteZeroSearch() && shaft_angle < _2PI){
153148
loopFOC();
@@ -204,7 +199,7 @@ int BLDCMotor::initFOC() {
204199
int exit_flag = alignSensor();
205200
_delay(500);
206201

207-
if(monitor_port) monitor_port->println("MONITOR: FOC init finished - motor ready.");
202+
if(monitor_port) monitor_port->println("MOT: Motor ready.");
208203

209204
return exit_flag;
210205
}
@@ -348,28 +343,21 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
348343
}
349344

350345
// set the voltages in hardware
351-
setPwm(pwmA, Ua);
352-
setPwm(pwmB, Ub);
353-
setPwm(pwmC, Uc);
346+
setPwm(Ua, Ub, Uc);
354347
}
355348

356349

357350

358351

359352
// Set voltage to the pwm pin
360-
// - function a bit optimized to get better performance
361-
void BLDCMotor::setPwm(int pinPwm, float U) {
362-
// max value
363-
float U_max = voltage_power_supply;
364-
365-
// sets the voltage [0,12V(U_max)] to pwm [0,255]
366-
// - U_max you can set in header file - default 12V
367-
int U_pwm = 255.0 * U / U_max;
368-
369-
// limit the values between 0 and 255
370-
U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm;
371-
372-
analogWrite(pinPwm, U_pwm);
353+
void BLDCMotor::setPwm(float Ua, float Ub, float Uc) {
354+
// calculate duty cycle
355+
// limited in [0,1]
356+
float dc_a = (Ua < 0) ? 0 : (Ua >= voltage_power_supply) ? 1 : Ua / voltage_power_supply;
357+
float dc_b = (Ub < 0) ? 0 : (Ub >= voltage_power_supply) ? 1 : Ub / voltage_power_supply;
358+
float dc_c = (Uc < 0) ? 0 : (Uc >= voltage_power_supply) ? 1 : Uc / voltage_power_supply;
359+
// hardware specific writing
360+
_writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC );
373361
}
374362

375363
/**
@@ -434,7 +422,7 @@ float BLDCMotor::positionP(float ek) {
434422
// function implementing the monitor_port setter
435423
void BLDCMotor::useMonitoring(Print &print){
436424
monitor_port = &print; //operate on the address of print
437-
if(monitor_port ) monitor_port->println("MONITOR: Serial monitor enabled!");
425+
if(monitor_port ) monitor_port->println("MOT: Monitor enabled!");
438426
}
439427
// utility function intended to be used with serial plotter to monitor motor variables
440428
// significantly slowing the execution down!!!!
@@ -478,51 +466,63 @@ int BLDCMotor::command(String user_command) {
478466
// parse command values
479467
float value = user_command.substring(1).toFloat();
480468

469+
// a bit of optimisation of variable memory for Arduino UNO (atmega328)
470+
switch(cmd){
471+
case 'P': // velocity P gain change
472+
case 'I': // velocity I gain change
473+
case 'L': // velocity voltage limit change
474+
case 'R': // velocity voltage ramp change
475+
if(monitor_port) monitor_port->print(" PI velocity| ");
476+
break;
477+
case 'F': // velocity Tf low pass filter change
478+
if(monitor_port) monitor_port->print(" LPF velocity| ");
479+
break;
480+
case 'K': // angle loop gain P change
481+
case 'N': // angle loop gain velocity_limit change
482+
if(monitor_port) monitor_port->print(" P angle| ");
483+
break;
484+
}
485+
481486
// apply the the command
482487
switch(cmd){
483488
case 'P': // velocity P gain change
484-
if(monitor_port) monitor_port->print("PI velocity P: ");
489+
if(monitor_port) monitor_port->print("P: ");
485490
if(!GET) PI_velocity.P = value;
486491
if(monitor_port) monitor_port->println(PI_velocity.P);
487492
break;
488493
case 'I': // velocity I gain change
489-
if(monitor_port) monitor_port->print("PI velocity I: ");
494+
if(monitor_port) monitor_port->print("I: ");
490495
if(!GET) PI_velocity.I = value;
491496
if(monitor_port) monitor_port->println(PI_velocity.I);
492497
break;
493498
case 'L': // velocity voltage limit change
494-
if(monitor_port) monitor_port->print("PI velocity voltage limit: ");
499+
if(monitor_port) monitor_port->print("volt_limit: ");
495500
if(!GET)PI_velocity.voltage_limit = value;
496501
if(monitor_port) monitor_port->println(PI_velocity.voltage_limit);
497502
break;
498503
case 'R': // velocity voltage ramp change
499-
if(monitor_port) monitor_port->print("PI velocity voltage ramp: ");
504+
if(monitor_port) monitor_port->print("volt_ramp: ");
500505
if(!GET) PI_velocity.voltage_ramp = value;
501506
if(monitor_port) monitor_port->println(PI_velocity.voltage_ramp);
502507
break;
503508
case 'F': // velocity Tf low pass filter change
504-
if(monitor_port) monitor_port->print("LPF velocity time constant: ");
509+
if(monitor_port) monitor_port->print("Tf: ");
505510
if(!GET) LPF_velocity.Tf = value;
506511
if(monitor_port) monitor_port->println(LPF_velocity.Tf);
507512
break;
508513
case 'K': // angle loop gain P change
509-
if(monitor_port) monitor_port->print("P angle P value: ");
514+
if(monitor_port) monitor_port->print(" P: ");
510515
if(!GET) P_angle.P = value;
511516
if(monitor_port) monitor_port->println(P_angle.P);
512517
break;
513518
case 'N': // angle loop gain velocity_limit change
514-
if(monitor_port) monitor_port->print("P angle velocity limit: ");
515-
if(!GET) P_angle.velocity_limit = value;
516-
if(monitor_port) monitor_port->println(P_angle.velocity_limit);
517-
break;
518-
case 'T': // angle loop gain velocity_limit change
519-
if(monitor_port) monitor_port->print("P angle velocity limit: ");
519+
if(monitor_port) monitor_port->print("vel_limit: ");
520520
if(!GET) P_angle.velocity_limit = value;
521521
if(monitor_port) monitor_port->println(P_angle.velocity_limit);
522522
break;
523523
case 'C':
524524
// change control type
525-
if(monitor_port) monitor_port->print("Contoller type: ");
525+
if(monitor_port) monitor_port->print("Control: ");
526526

527527
if(GET){ // if get commang
528528
switch(controller){
@@ -584,6 +584,4 @@ int BLDCMotor::command(String user_command) {
584584
}
585585
// return 0 if error and 1 if ok
586586
return errorFlag;
587-
}
588-
589-
587+
}

arduino_foc_minimal_encoder/BLDCMotor.h

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -245,8 +245,15 @@ class BLDCMotor
245245

246246
/** Electrical angle calculation */
247247
float electricAngle(float shaftAngle);
248-
/** Set phase voltaget to pwm output */
249-
void setPwm(int pinPwm, float U);
248+
249+
/**
250+
* Set phase voltages to the harware
251+
*
252+
* @param Ua phase A voltage
253+
* @param Ub phase B voltage
254+
* @param Uc phase C voltage
255+
*/
256+
void setPwm(float Ua, float Ub, float Uc);
250257

251258
// Utility functions
252259
/** normalizing radian angle to [0,2PI] */

0 commit comments

Comments
 (0)