@@ -60,14 +60,14 @@ 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
73
_setPwmFrequency (pwmA);
@@ -79,7 +79,7 @@ void BLDCMotor::init() {
79
79
80
80
_delay (500 );
81
81
// enable motor
82
- if (monitor_port) monitor_port->println (" MONITOR: Enabling motor ." );
82
+ if (monitor_port) monitor_port->println (" MOT: Enable ." );
83
83
enable ();
84
84
_delay (500 );
85
85
@@ -115,7 +115,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) {
115
115
116
116
// Encoder alignment to electrical 0 angle
117
117
int BLDCMotor::alignSensor () {
118
- if (monitor_port) monitor_port->println (" MONITOR : Align the sensor's and motor electrical 0 angle ." );
118
+ if (monitor_port) monitor_port->println (" MOT : Align sensor." );
119
119
// align the electrical phases of the motor and sensor
120
120
// set angle -90 degrees
121
121
setPhaseVoltage (voltage_sensor_align, _3PI_2);
@@ -131,9 +131,9 @@ int BLDCMotor::alignSensor() {
131
131
int exit_flag = absoluteZeroAlign ();
132
132
_delay (500 );
133
133
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!" );
134
+ if (exit_flag< 0 ) monitor_port->println (" MOT : Error: Not found!" );
135
+ if (exit_flag> 0 ) monitor_port->println (" MOT : Success!" );
136
+ else monitor_port->println (" MOT: Not available!" );
137
137
}
138
138
return exit_flag;
139
139
}
@@ -145,9 +145,9 @@ int BLDCMotor::absoluteZeroAlign() {
145
145
// if no absolute zero return
146
146
if (!sensor->hasAbsoluteZero ()) return 0 ;
147
147
148
- if (monitor_port) monitor_port->println (" MONITOR: Aligning the absolute zero." );
148
+ if (monitor_port) monitor_port->println (" MOT: Absolute zero align ." );
149
149
150
- if (monitor_port && sensor->needsAbsoluteZeroSearch ()) monitor_port->println (" MONITOR : Searching for absolute zero ." );
150
+ if (monitor_port && sensor->needsAbsoluteZeroSearch ()) monitor_port->println (" MOT : Searching.. ." );
151
151
// search the absolute zero with small velocity
152
152
while (sensor->needsAbsoluteZeroSearch () && shaft_angle < _2PI){
153
153
loopFOC ();
@@ -204,7 +204,7 @@ int BLDCMotor::initFOC() {
204
204
int exit_flag = alignSensor ();
205
205
_delay (500 );
206
206
207
- if (monitor_port) monitor_port->println (" MONITOR: FOC init finished - motor ready." );
207
+ if (monitor_port) monitor_port->println (" MOT: Motor ready." );
208
208
209
209
return exit_flag;
210
210
}
@@ -434,7 +434,7 @@ float BLDCMotor::positionP(float ek) {
434
434
// function implementing the monitor_port setter
435
435
void BLDCMotor::useMonitoring (Print &print){
436
436
monitor_port = &print; // operate on the address of print
437
- if (monitor_port ) monitor_port->println (" MONITOR: Serial monitor enabled!" );
437
+ if (monitor_port ) monitor_port->println (" MOT: Monitor enabled!" );
438
438
}
439
439
// utility function intended to be used with serial plotter to monitor motor variables
440
440
// significantly slowing the execution down!!!!
@@ -478,51 +478,63 @@ int BLDCMotor::command(String user_command) {
478
478
// parse command values
479
479
float value = user_command.substring (1 ).toFloat ();
480
480
481
+ // a bit of optimisation of variable memory for Arduino UNO (atmega328)
482
+ switch (cmd){
483
+ case ' P' : // velocity P gain change
484
+ case ' I' : // velocity I gain change
485
+ case ' L' : // velocity voltage limit change
486
+ case ' R' : // velocity voltage ramp change
487
+ if (monitor_port) monitor_port->print (" PI velocity| " );
488
+ break ;
489
+ case ' F' : // velocity Tf low pass filter change
490
+ if (monitor_port) monitor_port->print (" LPF velocity| " );
491
+ break ;
492
+ case ' K' : // angle loop gain P change
493
+ case ' N' : // angle loop gain velocity_limit change
494
+ if (monitor_port) monitor_port->print (" P angle| " );
495
+ break ;
496
+ }
497
+
481
498
// apply the the command
482
499
switch (cmd){
483
500
case ' P' : // velocity P gain change
484
- if (monitor_port) monitor_port->print (" PI velocity P: " );
501
+ if (monitor_port) monitor_port->print (" P: " );
485
502
if (!GET) PI_velocity.P = value;
486
503
if (monitor_port) monitor_port->println (PI_velocity.P );
487
504
break ;
488
505
case ' I' : // velocity I gain change
489
- if (monitor_port) monitor_port->print (" PI velocity I: " );
506
+ if (monitor_port) monitor_port->print (" I: " );
490
507
if (!GET) PI_velocity.I = value;
491
508
if (monitor_port) monitor_port->println (PI_velocity.I );
492
509
break ;
493
510
case ' L' : // velocity voltage limit change
494
- if (monitor_port) monitor_port->print (" PI velocity voltage limit : " );
511
+ if (monitor_port) monitor_port->print (" volt_limit : " );
495
512
if (!GET)PI_velocity.voltage_limit = value;
496
513
if (monitor_port) monitor_port->println (PI_velocity.voltage_limit );
497
514
break ;
498
515
case ' R' : // velocity voltage ramp change
499
- if (monitor_port) monitor_port->print (" PI velocity voltage ramp : " );
516
+ if (monitor_port) monitor_port->print (" volt_ramp : " );
500
517
if (!GET) PI_velocity.voltage_ramp = value;
501
518
if (monitor_port) monitor_port->println (PI_velocity.voltage_ramp );
502
519
break ;
503
520
case ' F' : // velocity Tf low pass filter change
504
- if (monitor_port) monitor_port->print (" LPF velocity time constant : " );
521
+ if (monitor_port) monitor_port->print (" Tf : " );
505
522
if (!GET) LPF_velocity.Tf = value;
506
523
if (monitor_port) monitor_port->println (LPF_velocity.Tf );
507
524
break ;
508
525
case ' K' : // angle loop gain P change
509
- if (monitor_port) monitor_port->print (" P angle P value : " );
526
+ if (monitor_port) monitor_port->print (" P : " );
510
527
if (!GET) P_angle.P = value;
511
528
if (monitor_port) monitor_port->println (P_angle.P );
512
529
break ;
513
530
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: " );
531
+ if (monitor_port) monitor_port->print (" vel_limit: " );
520
532
if (!GET) P_angle.velocity_limit = value;
521
533
if (monitor_port) monitor_port->println (P_angle.velocity_limit );
522
534
break ;
523
535
case ' C' :
524
536
// change control type
525
- if (monitor_port) monitor_port->print (" Contoller type : " );
537
+ if (monitor_port) monitor_port->print (" Control : " );
526
538
527
539
if (GET){ // if get commang
528
540
switch (controller){
0 commit comments