@@ -60,14 +60,14 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
6060
6161// init hardware pins
6262void 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
7373 _setPwmFrequency (pwmA);
@@ -79,7 +79,7 @@ void BLDCMotor::init() {
7979
8080 _delay (500 );
8181 // enable motor
82- if (monitor_port) monitor_port->println (" MONITOR: Enabling motor ." );
82+ if (monitor_port) monitor_port->println (" MOT: Enable ." );
8383 enable ();
8484 _delay (500 );
8585
@@ -115,7 +115,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) {
115115
116116// Encoder alignment to electrical 0 angle
117117int 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." );
119119 // align the electrical phases of the motor and sensor
120120 // set angle -90 degrees
121121 setPhaseVoltage (voltage_sensor_align, _3PI_2);
@@ -131,9 +131,9 @@ int BLDCMotor::alignSensor() {
131131 int exit_flag = absoluteZeroAlign ();
132132 _delay (500 );
133133 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!" );
137137 }
138138 return exit_flag;
139139}
@@ -145,9 +145,9 @@ int BLDCMotor::absoluteZeroAlign() {
145145 // if no absolute zero return
146146 if (!sensor->hasAbsoluteZero ()) return 0 ;
147147
148- if (monitor_port) monitor_port->println (" MONITOR: Aligning the absolute zero." );
148+ if (monitor_port) monitor_port->println (" MOT: Absolute zero align ." );
149149
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.. ." );
151151 // search the absolute zero with small velocity
152152 while (sensor->needsAbsoluteZeroSearch () && shaft_angle < _2PI){
153153 loopFOC ();
@@ -204,7 +204,7 @@ int BLDCMotor::initFOC() {
204204 int exit_flag = alignSensor ();
205205 _delay (500 );
206206
207- if (monitor_port) monitor_port->println (" MONITOR: FOC init finished - motor ready." );
207+ if (monitor_port) monitor_port->println (" MOT: Motor ready." );
208208
209209 return exit_flag;
210210}
@@ -434,7 +434,7 @@ float BLDCMotor::positionP(float ek) {
434434// function implementing the monitor_port setter
435435void BLDCMotor::useMonitoring (Print &print){
436436 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!" );
438438}
439439// utility function intended to be used with serial plotter to monitor motor variables
440440// significantly slowing the execution down!!!!
@@ -478,51 +478,63 @@ int BLDCMotor::command(String user_command) {
478478 // parse command values
479479 float value = user_command.substring (1 ).toFloat ();
480480
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+
481498 // apply the the command
482499 switch (cmd){
483500 case ' P' : // velocity P gain change
484- if (monitor_port) monitor_port->print (" PI velocity P: " );
501+ if (monitor_port) monitor_port->print (" P: " );
485502 if (!GET) PI_velocity.P = value;
486503 if (monitor_port) monitor_port->println (PI_velocity.P );
487504 break ;
488505 case ' I' : // velocity I gain change
489- if (monitor_port) monitor_port->print (" PI velocity I: " );
506+ if (monitor_port) monitor_port->print (" I: " );
490507 if (!GET) PI_velocity.I = value;
491508 if (monitor_port) monitor_port->println (PI_velocity.I );
492509 break ;
493510 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 : " );
495512 if (!GET)PI_velocity.voltage_limit = value;
496513 if (monitor_port) monitor_port->println (PI_velocity.voltage_limit );
497514 break ;
498515 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 : " );
500517 if (!GET) PI_velocity.voltage_ramp = value;
501518 if (monitor_port) monitor_port->println (PI_velocity.voltage_ramp );
502519 break ;
503520 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 : " );
505522 if (!GET) LPF_velocity.Tf = value;
506523 if (monitor_port) monitor_port->println (LPF_velocity.Tf );
507524 break ;
508525 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 : " );
510527 if (!GET) P_angle.P = value;
511528 if (monitor_port) monitor_port->println (P_angle.P );
512529 break ;
513530 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: " );
520532 if (!GET) P_angle.velocity_limit = value;
521533 if (monitor_port) monitor_port->println (P_angle.velocity_limit );
522534 break ;
523535 case ' C' :
524536 // change control type
525- if (monitor_port) monitor_port->print (" Contoller type : " );
537+ if (monitor_port) monitor_port->print (" Control : " );
526538
527539 if (GET){ // if get commang
528540 switch (controller){
0 commit comments