SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
Commander Class Reference

#include <Commander.h>

Public Member Functions

 Commander (Stream &serial, char eol='\n', bool echo=false)
 
 Commander (char eol='\n', bool echo=false)
 
void run ()
 
void run (Stream &reader, char eol='\n')
 
void run (char *user_input)
 
void add (char id, CommandCallback onCommand, const char *label=nullptr)
 
void motor (FOCMotor *motor, char *user_cmd)
 
void lpf (LowPassFilter *lpf, char *user_cmd)
 
void pid (PIDController *pid, char *user_cmd)
 
void scalar (float *value, char *user_cmd)
 
void target (FOCMotor *motor, char *user_cmd, char *separator=(char *)" ")
 
void motion (FOCMotor *motor, char *user_cmd, char *separator=(char *)" ")
 
bool isSentinel (char ch)
 

Public Attributes

VerboseMode verbose = VerboseMode::user_friendly
 flag signaling that the commands should output user understanable text
 
uint8_t decimal_places = 3
 number of decimal places to be used when displaying numbers
 
Stream * com_port = nullptr
 Serial terminal variable if provided.
 
char eol = '\n'
 end of line sentinel character
 
bool echo = false
 echo last typed character (for command line feedback)
 

Detailed Description

Commander class implementing string communication protocol based on IDvalue (ex AB5.321 - command id A, sub-command id B,value 5.321)

  • This class can be used in combination with HardwareSerial instance which it would read and write or it can be used to parse strings that have been received from the user outside this library
  • Commander class implements command protocol for few standard components of the SimpleFOC library
  • Commander also provides a very simple command > callback interface that enables user to attach a callback function to certain command id - see function add()

Definition at line 38 of file Commander.h.

Constructor & Destructor Documentation

◆ Commander() [1/2]

Commander::Commander ( Stream &  serial,
char  eol = '\n',
bool  echo = false 
)

Default constructor receiving a serial interface that it uses to output the values to Also if the function run() is used it uses this serial instance to read the serial for user commands

Parameters
serial- Serial com port instance
eol- the end of line sentinel character
echo- echo last typed character (for command line feedback)

Definition at line 3 of file Commander.cpp.

◆ Commander() [2/2]

Commander::Commander ( char  eol = '\n',
bool  echo = false 
)

Definition at line 8 of file Commander.cpp.

Member Function Documentation

◆ add()

void Commander::add ( char  id,
CommandCallback  onCommand,
const char *  label = nullptr 
)

Function adding a callback to the commander with the command id

Parameters
id- char command letter
onCommand- function pointer void function(char*)
label- string label to be displayed when scan command sent

Definition at line 14 of file Commander.cpp.

◆ isSentinel()

bool Commander::isSentinel ( char  ch)

Definition at line 659 of file Commander.cpp.

Here is the caller graph for this function:

◆ lpf()

void Commander::lpf ( LowPassFilter lpf,
char *  user_cmd 
)

Low pass fileter command interface

Parameters
lpf- LowPassFilter instance
user_cmd- the string command
  • It only has one property - filtering time constant Tf
  • It can be get by sending 'F'
  • It can be set by sending 'Fvalue' - (ex. F0.01 for settin Tf=0.01)

Definition at line 546 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ motion()

void Commander::motion ( FOCMotor motor,
char *  user_cmd,
char *  separator = (char *)" " 
)

FOC motor (StepperMotor and BLDCMotor) motion control interfaces

Parameters
motor- FOCMotor (BLDCMotor or StepperMotor) instance
user_cmd- the string command
separator- the string separator in between target and limit values, default is space - " "

Commands: 'C' - Motion control type config sub-commands: 'D' - downsample motiron loop '0' - torque '1' - velocity '2' - angle 'T' - Torque control type sub-commands: '0' - voltage '1' - current '2' - foc_current 'E' - Motor status (enable/disable) sub-commands: '0' - enable '1' - disable '' - Target setting interface Depends of the motion control mode:

  • torque : torque (ex. M2.5)
  • velocity (open and closed loop) : velocity torque (ex.M10 2.5 or M10 to only chanage the target witout limits)
  • angle (open and closed loop) : angle velocity torque (ex.M3.5 10 2.5 or M3.5 to only chanage the target witout limits)

Definition at line 417 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ motor()

void Commander::motor ( FOCMotor motor,
char *  user_cmd 
)

FOC motor (StepperMotor and BLDCMotor) command interface

Parameters
motor- FOCMotor (BLDCMotor or StepperMotor) instance
user_cmd- the string command
  • It has several paramters (the letters can be changed in the commands.h file) 'Q' - Q current PID controller & LPF (see function pid and lpf for commands) 'D' - D current PID controller & LPF (see function pid and lpf for commands) 'V' - Velocity PID controller & LPF (see function pid and lpf for commands) 'A' - Angle PID controller & LPF (see function pid and lpf for commands) 'L' - Limits sub-commands: 'C' - Current 'U' - Voltage 'V' - Velocity 'C' - Motion control type config sub-commands: 'D' - downsample motiron loop '0' - torque '1' - velocity '2' - angle 'T' - Torque control type sub-commands: '0' - voltage '1' - current '2' - foc_current 'E' - Motor status (enable/disable) sub-commands: '0' - enable '1' - disable 'R' - Motor resistance 'S' - Sensor offsets sub-commands: 'M' - sensor offset 'E' - sensor electrical zero 'M' - Monitoring control sub-commands: 'D' - downsample monitoring 'C' - clear monitor 'S' - set monitoring variables 'G' - get variable value '' - Target setting interface Depends of the motion control mode:
    • torque : torque (ex. M2.5)
    • velocity (open and closed loop) : velocity torque (ex.M10 2.5 or M10 to only chanage the target witout limits)
    • angle (open and closed loop) : angle velocity torque (ex.M3.5 10 2.5 or M3.5 to only chanage the target witout limits)
  • Each of them can be get by sening the command letter -(ex. 'R' - to get the phase resistance)
  • Each of them can be set by sending 'IdSubidValue' - (ex. SM1.5 for setting sensor zero offset to 1.5f)

Definition at line 107 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pid()

void Commander::pid ( PIDController pid,
char *  user_cmd 
)

PID controller command interface

Parameters
pid- PIDController instance
user_cmd- the string command
  • It has several paramters (the letters can be changed in the commands.h file)
    • P gain - 'P'
    • I gain - 'I'
    • D gain - 'D'
    • output ramp - 'R'
    • output limit - 'L'
  • Each of them can be get by sening the command letter -(ex. 'D' - to get the D gain)
  • Each of them can be set by sending 'IDvalue' - (ex. I1.5 for setting I=1.5)

Definition at line 509 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ run() [1/3]

void Commander::run ( )

Function reading the serial port and firing callbacks that have been added to the commander once the user has requested them - when he sends the command

  • It has default commands (the letters can be changed in the commands.h file) '@' - Verbose mode '#' - Number of decimal places '?' - Scan command - displays all the labels of attached nodes

Definition at line 22 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ run() [2/3]

void Commander::run ( char *  user_input)

Function reading the string of user input and firing callbacks that have been added to the commander once the user has requested them - when he sends the command

  • It has default commands (the letters can be changed in the commands.h file) '@' - Verbose mode '#' - Number of decimal places '?' - Scan command - displays all the labels of attached nodes
Parameters
user_input- string of user inputs

Definition at line 59 of file Commander.cpp.

Here is the call graph for this function:

◆ run() [3/3]

void Commander::run ( Stream &  reader,
char  eol = '\n' 
)

Function reading the string of user input and firing callbacks that have been added to the commander once the user has requested them - when he sends the command

  • It has default commands (the letters can be changed in the commands.h file) '@' - Verbose mode '#' - Number of decimal places '?' - Scan command - displays all the labels of attached nodes
Parameters
reader- temporary stream to read user input
eol- temporary end of line sentinel

Definition at line 27 of file Commander.cpp.

Here is the call graph for this function:

◆ scalar()

void Commander::scalar ( float *  value,
char *  user_cmd 
)

Float variable scalar command interface

Parameters
value- float variable pointer
user_cmd- the string command
  • It only has one property - one float value
  • It can be get by sending an empty string '
    '
  • It can be set by sending 'value' - (ex. 0.01f for settin *value=0.01)

Definition at line 563 of file Commander.cpp.

Here is the call graph for this function:

◆ target()

void Commander::target ( FOCMotor motor,
char *  user_cmd,
char *  separator = (char *)" " 
)

Target setting interface, enables setting the target and limiting variables at once. The values are sent separated by a separator specified as the third argument. The default separator is the space.

Parameters
motor- FOCMotor (BLDCMotor or StepperMotor) instance
user_cmd- the string command
separator- the string separator in between target and limit values, default is space - " "

Example: P2.34 70 2 P is the user defined command, 2.34 is the target angle 70 is the target velocity and 2 is the desired max current.

It depends of the motion control mode:

  • torque : torque (ex. P2.5)
  • velocity : velocity torque (ex.P10 2.5 or P10 to only chanage the target witout limits)
  • angle : angle velocity torque (ex.P3.5 10 2.5 or P3.5 to only chanage the target witout limits)

Definition at line 570 of file Commander.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ com_port

Stream* Commander::com_port = nullptr

Serial terminal variable if provided.

Definition at line 101 of file Commander.h.

◆ decimal_places

uint8_t Commander::decimal_places = 3

number of decimal places to be used when displaying numbers

Definition at line 98 of file Commander.h.

◆ echo

bool Commander::echo = false

echo last typed character (for command line feedback)

Definition at line 103 of file Commander.h.

◆ eol

char Commander::eol = '\n'

end of line sentinel character

Definition at line 102 of file Commander.h.

◆ verbose

flag signaling that the commands should output user understanable text

Definition at line 97 of file Commander.h.


The documentation for this class was generated from the following files: