@@ -60,26 +60,24 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
60
60
61
61
// init hardware pins
62
62
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." );
64
64
// PWM pins
65
65
pinMode (pwmA, OUTPUT);
66
66
pinMode (pwmB, OUTPUT);
67
67
pinMode (pwmC, OUTPUT);
68
68
if (hasEnable ()) pinMode (enable_pin, OUTPUT);
69
69
70
- if (monitor_port) monitor_port->println (" MONITOR: Set high frequency PWM." );
70
+ if (monitor_port) monitor_port->println (" MOT: PWM config ." );
71
71
// Increase PWM frequency to 32 kHz
72
72
// make silent
73
- _setPwmFrequency (pwmA);
74
- _setPwmFrequency (pwmB);
75
- _setPwmFrequency (pwmC);
73
+ _setPwmFrequency (pwmA, pwmB, pwmC);
76
74
77
75
// sanity check for the voltage limit configuration
78
76
if (PI_velocity.voltage_limit > voltage_power_supply) PI_velocity.voltage_limit = voltage_power_supply;
79
77
80
78
_delay (500 );
81
79
// enable motor
82
- if (monitor_port) monitor_port->println (" MONITOR: Enabling motor ." );
80
+ if (monitor_port) monitor_port->println (" MOT: Enable ." );
83
81
enable ();
84
82
_delay (500 );
85
83
@@ -92,17 +90,13 @@ void BLDCMotor::disable()
92
90
// disable the driver - if enable_pin pin available
93
91
if (hasEnable ()) digitalWrite (enable_pin, LOW);
94
92
// set zero to PWM
95
- setPwm (pwmA, 0 );
96
- setPwm (pwmB, 0 );
97
- setPwm (pwmC, 0 );
93
+ setPwm (0 , 0 , 0 );
98
94
}
99
95
// enable motor driver
100
96
void BLDCMotor::enable ()
101
97
{
102
98
// set zero to PWM
103
- setPwm (pwmA, 0 );
104
- setPwm (pwmB, 0 );
105
- setPwm (pwmC, 0 );
99
+ setPwm (0 , 0 , 0 );
106
100
// enable_pin the driver - if enable_pin pin available
107
101
if (hasEnable ()) digitalWrite (enable_pin, HIGH);
108
102
@@ -115,7 +109,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) {
115
109
116
110
// Encoder alignment to electrical 0 angle
117
111
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." );
119
113
// align the electrical phases of the motor and sensor
120
114
// set angle -90 degrees
121
115
setPhaseVoltage (voltage_sensor_align, _3PI_2);
@@ -131,9 +125,9 @@ int BLDCMotor::alignSensor() {
131
125
int exit_flag = absoluteZeroAlign ();
132
126
_delay (500 );
133
127
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!" );
137
131
}
138
132
return exit_flag;
139
133
}
@@ -142,12 +136,13 @@ int BLDCMotor::alignSensor() {
142
136
// Encoder alignment the absolute zero angle
143
137
// - to the index
144
138
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
146
142
if (!sensor->hasAbsoluteZero ()) return 0 ;
147
143
148
- if (monitor_port) monitor_port->println (" MONITOR: Aligning the absolute zero." );
149
144
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.. ." );
151
146
// search the absolute zero with small velocity
152
147
while (sensor->needsAbsoluteZeroSearch () && shaft_angle < _2PI){
153
148
loopFOC ();
@@ -204,7 +199,7 @@ int BLDCMotor::initFOC() {
204
199
int exit_flag = alignSensor ();
205
200
_delay (500 );
206
201
207
- if (monitor_port) monitor_port->println (" MONITOR: FOC init finished - motor ready." );
202
+ if (monitor_port) monitor_port->println (" MOT: Motor ready." );
208
203
209
204
return exit_flag;
210
205
}
@@ -348,28 +343,21 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
348
343
}
349
344
350
345
// set the voltages in hardware
351
- setPwm (pwmA, Ua);
352
- setPwm (pwmB, Ub);
353
- setPwm (pwmC, Uc);
346
+ setPwm (Ua, Ub, Uc);
354
347
}
355
348
356
349
357
350
358
351
359
352
// 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 );
373
361
}
374
362
375
363
/* *
@@ -434,7 +422,7 @@ float BLDCMotor::positionP(float ek) {
434
422
// function implementing the monitor_port setter
435
423
void BLDCMotor::useMonitoring (Print &print){
436
424
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!" );
438
426
}
439
427
// utility function intended to be used with serial plotter to monitor motor variables
440
428
// significantly slowing the execution down!!!!
@@ -478,51 +466,63 @@ int BLDCMotor::command(String user_command) {
478
466
// parse command values
479
467
float value = user_command.substring (1 ).toFloat ();
480
468
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
+
481
486
// apply the the command
482
487
switch (cmd){
483
488
case ' P' : // velocity P gain change
484
- if (monitor_port) monitor_port->print (" PI velocity P: " );
489
+ if (monitor_port) monitor_port->print (" P: " );
485
490
if (!GET) PI_velocity.P = value;
486
491
if (monitor_port) monitor_port->println (PI_velocity.P );
487
492
break ;
488
493
case ' I' : // velocity I gain change
489
- if (monitor_port) monitor_port->print (" PI velocity I: " );
494
+ if (monitor_port) monitor_port->print (" I: " );
490
495
if (!GET) PI_velocity.I = value;
491
496
if (monitor_port) monitor_port->println (PI_velocity.I );
492
497
break ;
493
498
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 : " );
495
500
if (!GET)PI_velocity.voltage_limit = value;
496
501
if (monitor_port) monitor_port->println (PI_velocity.voltage_limit );
497
502
break ;
498
503
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 : " );
500
505
if (!GET) PI_velocity.voltage_ramp = value;
501
506
if (monitor_port) monitor_port->println (PI_velocity.voltage_ramp );
502
507
break ;
503
508
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 : " );
505
510
if (!GET) LPF_velocity.Tf = value;
506
511
if (monitor_port) monitor_port->println (LPF_velocity.Tf );
507
512
break ;
508
513
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 : " );
510
515
if (!GET) P_angle.P = value;
511
516
if (monitor_port) monitor_port->println (P_angle.P );
512
517
break ;
513
518
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: " );
520
520
if (!GET) P_angle.velocity_limit = value;
521
521
if (monitor_port) monitor_port->println (P_angle.velocity_limit );
522
522
break ;
523
523
case ' C' :
524
524
// change control type
525
- if (monitor_port) monitor_port->print (" Contoller type : " );
525
+ if (monitor_port) monitor_port->print (" Control : " );
526
526
527
527
if (GET){ // if get commang
528
528
switch (controller){
@@ -584,6 +584,4 @@ int BLDCMotor::command(String user_command) {
584
584
}
585
585
// return 0 if error and 1 if ok
586
586
return errorFlag;
587
- }
588
-
589
-
587
+ }
0 commit comments