SimpleFOClibrary  2.1
BLDCMotor.cpp
Go to the documentation of this file.
1 #include "BLDCMotor.h"
2 
3 // BLDCMotor( int pp , float R)
4 // - pp - pole pair number
5 // - R - motor phase resistance
6 BLDCMotor::BLDCMotor(int pp, float _R)
7 : FOCMotor()
8 {
9  // save pole pairs number
10  pole_pairs = pp;
11  // save phase resistance number
12  phase_resistance = _R;
13  // torque control type is voltage by default
15 }
16 
17 
22  driver = _driver;
23 }
24 
25 // init hardware pins
27  if(monitor_port) monitor_port->println(F("MOT: Init"));
28 
29  // if no current sensing and the user has set the phase resistance of the motor use current limit to calculate the voltage limit
31  float new_voltage_limit = current_limit * (phase_resistance); // v_lim = current_lim / (3/2 phase resistance) - worst case
32  // use it if it is less then voltage_limit set by the user
33  voltage_limit = new_voltage_limit < voltage_limit ? new_voltage_limit : voltage_limit;
34  }
35  // sanity check for the voltage limit configuration
37  // constrain voltage for sensor alignment
39 
40  // update the controller limits
41  if(current_sense){
42  // current control loop controls voltage
45  // velocity control loop controls current
47  }else{
49  }
51 
52  _delay(500);
53  // enable motor
54  if(monitor_port) monitor_port->println(F("MOT: Enable driver."));
55  enable();
56  _delay(500);
57 }
58 
59 
60 // disable motor driver
62 {
63  // set zero to PWM
64  driver->setPwm(0, 0, 0);
65  // disable the driver
66  driver->disable();
67  // motor status update
68  enabled = 0;
69 }
70 // enable motor driver
72 {
73  // enable the driver
74  driver->enable();
75  // set zero to PWM
76  driver->setPwm(0, 0, 0);
77  // motor status update
78  enabled = 1;
79 }
80 
84 // FOC initialization function
85 int BLDCMotor::initFOC( float zero_electric_offset, Direction _sensor_direction) {
86  int exit_flag = 1;
87  // align motor if necessary
88  // alignment necessary for encoders!
89  if(_isset(zero_electric_offset)){
90  // abosolute zero offset provided - no need to align
91  zero_electric_angle = zero_electric_offset;
92  // set the sensor direction - default CW
93  sensor_direction = _sensor_direction;
94  }
95 
96  // sensor and motor alignment - can be skipped
97  // by setting motor.sensor_direction and motor.zero_electric_angle
98  _delay(500);
99  if(sensor) exit_flag *= alignSensor();
100  else if(monitor_port) monitor_port->println(F("MOT: No sensor."));
101 
102  // aligning the current sensor - can be skipped
103  // checks if driver phases are the same as current sense phases
104  // and checks the direction of measuremnt.
105  _delay(500);
106  if(exit_flag){
107  if(current_sense) exit_flag *= alignCurrentSense();
108  else if(monitor_port) monitor_port->println(F("MOT: No current sense."));
109  }
110 
111  if(exit_flag){
112  if(monitor_port) monitor_port->println(F("MOT: Ready."));
113  }else{
114  if(monitor_port) monitor_port->println(F("MOT: Init FOC failed."));
115  disable();
116  }
117 
118  return exit_flag;
119 }
120 
121 // Calibarthe the motor and current sense phases
122 int BLDCMotor::alignCurrentSense() {
123  int exit_flag = 1; // success
124 
125  if(monitor_port) monitor_port->println(F("MOT: Align current sense."));
126 
127  // align current sense and the driver
129  if(!exit_flag){
130  // error in current sense - phase either not measured or bad connection
131  if(monitor_port) monitor_port->println(F("MOT: Align error!"));
132  exit_flag = 0;
133  }else{
134  // output the alignment status flag
135  if(monitor_port) monitor_port->print(F("MOT: Success: "));
136  if(monitor_port) monitor_port->println(exit_flag);
137  }
138 
139  return exit_flag > 0;
140 }
141 
142 // Encoder alignment to electrical 0 angle
143 int BLDCMotor::alignSensor() {
144  int exit_flag = 1; //success
145  if(monitor_port) monitor_port->println(F("MOT: Align sensor."));
146 
147  // if unknown natural direction
148  if(!_isset(sensor_direction)){
149  // check if sensor needs zero search
150  if(sensor->needsSearch()) exit_flag = absoluteZeroSearch();
151  // stop init if not found index
152  if(!exit_flag) return exit_flag;
153 
154  // find natural direction
155  // move one electrical revolution forward
156  for (int i = 0; i <=500; i++ ) {
157  float angle = _3PI_2 + _2PI * i / 500.0;
158  setPhaseVoltage(voltage_sensor_align, 0, angle);
159  _delay(2);
160  }
161  // take and angle in the middle
162  float mid_angle = sensor->getAngle();
163  // move one electrical revolution backwards
164  for (int i = 500; i >=0; i-- ) {
165  float angle = _3PI_2 + _2PI * i / 500.0 ;
166  setPhaseVoltage(voltage_sensor_align, 0, angle);
167  _delay(2);
168  }
169  float end_angle = sensor->getAngle();
170  setPhaseVoltage(0, 0, 0);
171  _delay(200);
172  // determine the direction the sensor moved
173  if (mid_angle == end_angle) {
174  if(monitor_port) monitor_port->println(F("MOT: Failed to notice movement"));
175  return 0; // failed calibration
176  } else if (mid_angle < end_angle) {
177  if(monitor_port) monitor_port->println(F("MOT: sensor_direction==CCW"));
179  } else{
180  if(monitor_port) monitor_port->println(F("MOT: sensor_direction==CW"));
182  }
183  // check pole pair number
184  if(monitor_port) monitor_port->print(F("MOT: PP check: "));
185  float moved = fabs(mid_angle - end_angle);
186  if( fabs(moved*pole_pairs - _2PI) > 0.5 ) { // 0.5 is arbitrary number it can be lower or higher!
187  if(monitor_port) monitor_port->print(F("fail - estimated pp:"));
188  if(monitor_port) monitor_port->println(_2PI/moved,4);
189  }else if(monitor_port) monitor_port->println(F("OK!"));
190 
191  }else if(monitor_port) monitor_port->println(F("MOT: Skip dir calib."));
192 
193  // zero electric angle not known
195  // align the electrical phases of the motor and sensor
196  // set angle -90(270 = 3PI/2) degrees
197  setPhaseVoltage(voltage_sensor_align, 0, _3PI_2);
198  _delay(700);
200  _delay(20);
201  if(monitor_port){
202  monitor_port->print(F("MOT: Zero elec. angle: "));
204  }
205  // stop everything
206  setPhaseVoltage(0, 0, 0);
207  _delay(200);
208  }else if(monitor_port) monitor_port->println(F("MOT: Skip offset calib."));
209  return exit_flag;
210 }
211 
212 // Encoder alignment the absolute zero angle
213 // - to the index
214 int BLDCMotor::absoluteZeroSearch() {
215 
216  if(monitor_port) monitor_port->println(F("MOT: Index search..."));
217  // search the absolute zero with small velocity
218  float limit_vel = velocity_limit;
219  float limit_volt = voltage_limit;
222  shaft_angle = 0;
223  while(sensor->needsSearch() && shaft_angle < _2PI){
224  angleOpenloop(1.5*_2PI);
225  // call important for some sensors not to loose count
226  // not needed for the search
227  sensor->getAngle();
228  }
229  // disable motor
230  setPhaseVoltage(0, 0, 0);
231  // reinit the limits
232  velocity_limit = limit_vel;
233  voltage_limit = limit_volt;
234  // check if the zero found
235  if(monitor_port){
236  if(sensor->needsSearch()) monitor_port->println(F("MOT: Error: Not found!"));
237  else monitor_port->println(F("MOT: Success!"));
238  }
239  return !sensor->needsSearch();
240 }
241 
242 // Iterative function looping FOC algorithm, setting Uq on the Motor
243 // The faster it can be run the better
245  // if disabled do nothing
246  if(!enabled) return;
247  // if open-loop do nothing
249 
250  // shaft angle
252  // electrical angle - need shaftAngle to be called first
254 
255  switch (torque_controller) {
257  // no need to do anything really
258  break;
260  if(!current_sense) return;
261  // read overall current magnitude
263  // filter the value values
265  // calculate the phase voltage
267  voltage.d = 0;
268  break;
270  if(!current_sense) return;
271  // read dq currents
273  // filter values
276  // calculate the phase voltages
279  break;
280  default:
281  // no torque control selected
282  if(monitor_port) monitor_port->println(F("MOT: no torque control selected!"));
283  break;
284  }
285 
286  // set the phase voltage - FOC heart function :)
287  setPhaseVoltage(voltage.q, voltage.d, electrical_angle);
288 }
289 
290 // Iterative function running outer loop of the FOC algorithm
291 // Behavior of this function is determined by the motor.controller variable
292 // It runs either angle, velocity or torque loop
293 // - needs to be called iteratively it is asynchronous function
294 // - if target is not set it uses motor.target value
295 void BLDCMotor::move(float new_target) {
296  // if disabled do nothing
297  if(!enabled) return;
298  // downsampling (optional)
299  if(motion_cnt++ < motion_downsample) return;
300  motion_cnt = 0;
301  // set internal target variable
302  if(_isset(new_target)) target = new_target;
303  // get angular velocity
305 
306  switch (controller) {
308  if(torque_controller == TorqueControlType::voltage) // if voltage torque control
311  else
312  current_sp = target; // if current/foc_current torque control
313  break;
315  // angle set point
317  // calculate velocity set point
319  // calculate the torque command
320  current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if voltage torque control
321  // if torque controlled through voltage
323  // use voltage if phase-resistance not provided
326  voltage.d = 0;
327  }
328  break;
330  // velocity set point
332  // calculate the torque command
333  current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if current/foc_current torque control
334  // if torque controlled through voltage control
336  // use voltage if phase-resistance not provided
339  voltage.d = 0;
340  }
341  break;
343  // velocity control in open loop
345  voltage.q = velocityOpenloop(shaft_velocity_sp); // returns the voltage that is set to the motor
346  voltage.d = 0;
347  break;
349  // angle control in open loop
351  voltage.q = angleOpenloop(shaft_angle_sp); // returns the voltage that is set to the motor
352  voltage.d = 0;
353  break;
354  }
355 }
356 
357 
358 // Method using FOC to set Uq and Ud to the motor at the optimal angle
359 // Function implementing Space Vector PWM and Sine PWM algorithms
360 //
361 // Function using sine approximation
362 // regular sin + cos ~300us (no memory usaage)
363 // approx _sin + _cos ~110us (400Byte ~ 20% of memory)
364 void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) {
365 
366  float center;
367  int sector;
368  float _ca,_sa;
369 
370  switch (foc_modulation)
371  {
373  // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5
374  static int trap_120_map[6][3] = {
375  {_HIGH_IMPEDANCE,1,-1},{-1,1,_HIGH_IMPEDANCE},{-1,_HIGH_IMPEDANCE,1},{_HIGH_IMPEDANCE,-1,1},{1,-1,_HIGH_IMPEDANCE},{1,_HIGH_IMPEDANCE,-1} // each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z
376  };
377  // static int trap_120_state = 0;
378  sector = 6 * (_normalizeAngle(angle_el + _PI_6 ) / _2PI); // adding PI/6 to align with other modes
379  // centering the voltages around either
380  // modulation_centered == true > driver.volage_limit/2
381  // modulation_centered == false > or Adaptable centering, all phases drawn to 0 when Uq=0
382  center = modulation_centered ? (driver->voltage_limit)/2 : Uq;
383 
384  if(trap_120_map[sector][0] == _HIGH_IMPEDANCE){
385  Ua= center;
386  Ub = trap_120_map[sector][1] * Uq + center;
387  Uc = trap_120_map[sector][2] * Uq + center;
388  driver->setPhaseState(_HIGH_IMPEDANCE, _ACTIVE, _ACTIVE); // disable phase if possible
389  }else if(trap_120_map[sector][1] == _HIGH_IMPEDANCE){
390  Ua = trap_120_map[sector][0] * Uq + center;
391  Ub = center;
392  Uc = trap_120_map[sector][2] * Uq + center;
393  driver->setPhaseState(_ACTIVE, _HIGH_IMPEDANCE, _ACTIVE);// disable phase if possible
394  }else{
395  Ua = trap_120_map[sector][0] * Uq + center;
396  Ub = trap_120_map[sector][1] * Uq + center;
397  Uc = center;
398  driver->setPhaseState(_ACTIVE,_ACTIVE, _HIGH_IMPEDANCE);// disable phase if possible
399  }
400 
401  break;
402 
404  // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8
405  static int trap_150_map[12][3] = {
406  {_HIGH_IMPEDANCE,1,-1},{-1,1,-1},{-1,1,_HIGH_IMPEDANCE},{-1,1,1},{-1,_HIGH_IMPEDANCE,1},{-1,-1,1},{_HIGH_IMPEDANCE,-1,1},{1,-1,1},{1,-1,_HIGH_IMPEDANCE},{1,-1,-1},{1,_HIGH_IMPEDANCE,-1},{1,1,-1} // each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z
407  };
408  // static int trap_150_state = 0;
409  sector = 12 * (_normalizeAngle(angle_el + _PI_6 ) / _2PI); // adding PI/6 to align with other modes
410  // centering the voltages around either
411  // modulation_centered == true > driver.volage_limit/2
412  // modulation_centered == false > or Adaptable centering, all phases drawn to 0 when Uq=0
413  center = modulation_centered ? (driver->voltage_limit)/2 : Uq;
414 
415  if(trap_150_map[sector][0] == _HIGH_IMPEDANCE){
416  Ua= center;
417  Ub = trap_150_map[sector][1] * Uq + center;
418  Uc = trap_150_map[sector][2] * Uq + center;
419  driver->setPhaseState(_HIGH_IMPEDANCE, _ACTIVE, _ACTIVE); // disable phase if possible
420  }else if(trap_150_map[sector][1] == _HIGH_IMPEDANCE){
421  Ua = trap_150_map[sector][0] * Uq + center;
422  Ub = center;
423  Uc = trap_150_map[sector][2] * Uq + center;
424  driver->setPhaseState(_ACTIVE, _HIGH_IMPEDANCE, _ACTIVE);// disable phase if possible
425  }else{
426  Ua = trap_150_map[sector][0] * Uq + center;
427  Ub = trap_150_map[sector][1] * Uq + center;
428  Uc = center;
429  driver->setPhaseState(_ACTIVE, _ACTIVE, _HIGH_IMPEDANCE);// disable phase if possible
430  }
431 
432  break;
433 
435  // Sinusoidal PWM modulation
436  // Inverse Park + Clarke transformation
437 
438  // angle normalization in between 0 and 2pi
439  // only necessary if using _sin and _cos - approximation functions
440  angle_el = _normalizeAngle(angle_el);
441  _ca = _cos(angle_el);
442  _sa = _sin(angle_el);
443  // Inverse park transform
444  Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq;
445  Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq;
446 
447  // center = modulation_centered ? (driver->voltage_limit)/2 : Uq;
448  center = driver->voltage_limit/2;
449  // Clarke transform
450  Ua = Ualpha + center;
451  Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + center;
452  Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + center;
453 
454  if (!modulation_centered) {
455  float Umin = min(Ua, min(Ub, Uc));
456  Ua -= Umin;
457  Ub -= Umin;
458  Uc -= Umin;
459  }
460 
461  break;
462 
464  // Nice video explaining the SpaceVectorModulation (SVPWM) algorithm
465  // https://www.youtube.com/watch?v=QMSWUMEAejg
466 
467  // the algorithm goes
468  // 1) Ualpha, Ubeta
469  // 2) Uout = sqrt(Ualpha^2 + Ubeta^2)
470  // 3) angle_el = atan2(Ubeta, Ualpha)
471  //
472  // equivalent to 2) because the magnitude does not change is:
473  // Uout = sqrt(Ud^2 + Uq^2)
474  // equivalent to 3) is
475  // angle_el = angle_el + atan2(Uq,Ud)
476 
477  float Uout;
478  // a bit of optitmisation
479  if(Ud){ // only if Ud and Uq set
480  // _sqrt is an approx of sqrt (3-4% error)
481  Uout = _sqrt(Ud*Ud + Uq*Uq) / driver->voltage_limit;
482  // angle normalisation in between 0 and 2pi
483  // only necessary if using _sin and _cos - approximation functions
484  angle_el = _normalizeAngle(angle_el + atan2(Uq, Ud));
485  }else{// only Uq available - no need for atan2 and sqrt
486  Uout = Uq / driver->voltage_limit;
487  // angle normalisation in between 0 and 2pi
488  // only necessary if using _sin and _cos - approximation functions
489  angle_el = _normalizeAngle(angle_el + _PI_2);
490  }
491  // find the sector we are in currently
492  sector = floor(angle_el / _PI_3) + 1;
493  // calculate the duty cycles
494  float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uout;
495  float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uout;
496  // two versions possible
497  float T0 = 0; // pulled to 0 - better for low power supply voltage
498  if (modulation_centered) {
499  T0 = 1 - T1 - T2; //modulation_centered around driver->voltage_limit/2
500  }
501 
502  // calculate the duty cycles(times)
503  float Ta,Tb,Tc;
504  switch(sector){
505  case 1:
506  Ta = T1 + T2 + T0/2;
507  Tb = T2 + T0/2;
508  Tc = T0/2;
509  break;
510  case 2:
511  Ta = T1 + T0/2;
512  Tb = T1 + T2 + T0/2;
513  Tc = T0/2;
514  break;
515  case 3:
516  Ta = T0/2;
517  Tb = T1 + T2 + T0/2;
518  Tc = T2 + T0/2;
519  break;
520  case 4:
521  Ta = T0/2;
522  Tb = T1+ T0/2;
523  Tc = T1 + T2 + T0/2;
524  break;
525  case 5:
526  Ta = T2 + T0/2;
527  Tb = T0/2;
528  Tc = T1 + T2 + T0/2;
529  break;
530  case 6:
531  Ta = T1 + T2 + T0/2;
532  Tb = T0/2;
533  Tc = T1 + T0/2;
534  break;
535  default:
536  // possible error state
537  Ta = 0;
538  Tb = 0;
539  Tc = 0;
540  }
541 
542  // calculate the phase voltages and center
543  Ua = Ta*driver->voltage_limit;
544  Ub = Tb*driver->voltage_limit;
545  Uc = Tc*driver->voltage_limit;
546  break;
547 
548  }
549 
550  // set the voltages in driver
551  driver->setPwm(Ua, Ub, Uc);
552 }
553 
554 
555 
556 // Function (iterative) generating open loop movement for target velocity
557 // - target_velocity - rad/s
558 // it uses voltage_limit variable
559 float BLDCMotor::velocityOpenloop(float target_velocity){
560  // get current timestamp
561  unsigned long now_us = _micros();
562  // calculate the sample time from last call
563  float Ts = (now_us - open_loop_timestamp) * 1e-6;
564  // quick fix for strange cases (micros overflow + timestamp not defined)
565  if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
566 
567  // calculate the necessary angle to achieve target velocity
568  shaft_angle = _normalizeAngle(shaft_angle + target_velocity*Ts);
569  // for display purposes
570  shaft_velocity = target_velocity;
571 
572  // use voltage limit or current limit
573  float Uq = voltage_limit;
575 
576  // set the maximal allowed voltage (voltage_limit) with the necessary angle
577  setPhaseVoltage(Uq, 0, _electricalAngle(shaft_angle, pole_pairs));
578 
579  // save timestamp for next call
580  open_loop_timestamp = now_us;
581 
582  return Uq;
583 }
584 
585 // Function (iterative) generating open loop movement towards the target angle
586 // - target_angle - rad
587 // it uses voltage_limit and velocity_limit variables
588 float BLDCMotor::angleOpenloop(float target_angle){
589  // get current timestamp
590  unsigned long now_us = _micros();
591  // calculate the sample time from last call
592  float Ts = (now_us - open_loop_timestamp) * 1e-6;
593  // quick fix for strange cases (micros overflow + timestamp not defined)
594  if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
595 
596  // calculate the necessary angle to move from current position towards target angle
597  // with maximal velocity (velocity_limit)
598  if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)){
599  shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts;
601  }else{
602  shaft_angle = target_angle;
603  shaft_velocity = 0;
604  }
605 
606 
607  // use voltage limit or current limit
608  float Uq = voltage_limit;
610  // set the maximal allowed voltage (voltage_limit) with the necessary angle
611  setPhaseVoltage(Uq, 0, _electricalAngle(shaft_angle, pole_pairs));
612 
613  // save timestamp for next call
614  open_loop_timestamp = now_us;
615 
616  return Uq;
617 }
velocity_openloop
@ velocity_openloop
Definition: FOCMotor.h:31
_sin
float _sin(float a)
Definition: foc_utils.cpp:14
FOCMotor::current_sp
float current_sp
target current ( q current )
Definition: FOCMotor.h:135
Trapezoid_120
@ Trapezoid_120
Definition: FOCMotor.h:50
CW
@ CW
Definition: Sensor.h:8
FOCMotor
Definition: FOCMotor.h:58
BLDCDriver
Definition: BLDCDriver.h:6
FOCMotor::zero_electric_angle
float zero_electric_angle
absolute zero electric angle - if available
Definition: FOCMotor.h:180
Sensor::needsSearch
virtual int needsSearch()
Definition: Sensor.cpp:10
_SQRT3_2
#define _SQRT3_2
Definition: foc_utils.h:17
BLDCMotor::disable
void disable() override
Definition: BLDCMotor.cpp:61
voltage
@ voltage
Torque control using voltage.
Definition: FOCMotor.h:39
BLDCMotor::Ua
float Ua
Definition: BLDCMotor.h:69
FOCMotor::shaftAngle
float shaftAngle()
Definition: FOCMotor.cpp:56
FOCMotor::voltage_limit
float voltage_limit
Voltage limitting variable - global limit.
Definition: FOCMotor.h:150
_sqrt
#define _sqrt(a)
Definition: foc_utils.h:10
BLDCMotor::Ubeta
float Ubeta
Phase voltages U alpha and U beta used for inverse Park and Clarke transform.
Definition: BLDCMotor.h:70
FOCMotor::PID_current_d
PIDController PID_current_d
parameter determining the d current PID config
Definition: FOCMotor.h:168
angle
@ angle
Position/angle motion control.
Definition: FOCMotor.h:30
_isset
#define _isset(a)
Definition: foc_utils.h:11
_PI_3
#define _PI_3
Definition: foc_utils.h:22
BLDCDriver::voltage_limit
float voltage_limit
limiting voltage set to the motor
Definition: BLDCDriver.h:18
_delay
void _delay(unsigned long ms)
Definition: time_utils.cpp:5
DQVoltage_s::d
float d
Definition: foc_utils.h:48
FOCMotor::electricalAngle
float electricalAngle()
Definition: FOCMotor.cpp:68
FOCMotor::electrical_angle
float electrical_angle
current electrical angle
Definition: FOCMotor.h:133
FOCMotor::shaft_velocity_sp
float shaft_velocity_sp
current target velocity
Definition: FOCMotor.h:136
velocity
@ velocity
Velocity motion control.
Definition: FOCMotor.h:29
torque
@ torque
Torque control.
Definition: FOCMotor.h:28
FOCMotor::LPF_current_d
LowPassFilter LPF_current_d
parameter determining the current Low pass filter configuration
Definition: FOCMotor.h:170
BLDCMotor::initFOC
int initFOC(float zero_electric_offset=NOT_SET, Direction sensor_direction=Direction::CW) override
Definition: BLDCMotor.cpp:85
BLDCMotor.h
BLDCMotor::enable
void enable() override
Definition: BLDCMotor.cpp:71
FOCMotor::shaft_velocity
float shaft_velocity
current motor velocity
Definition: FOCMotor.h:134
FOCMotor::enabled
int8_t enabled
enabled or disabled motor flag
Definition: FOCMotor.h:155
FOCMotor::foc_modulation
FOCModulationType foc_modulation
parameter derterniming modulation algorithm
Definition: FOCMotor.h:158
FOCMotor::shaft_angle
float shaft_angle
current motor angle
Definition: FOCMotor.h:132
FOCMotor::target
float target
current target value - depends of the controller
Definition: FOCMotor.h:131
BLDCDriver::setPwm
virtual void setPwm(float Ua, float Ub, float Uc)=0
FOCMotor::phase_resistance
float phase_resistance
motor phase resistance
Definition: FOCMotor.h:146
_HIGH_IMPEDANCE
#define _HIGH_IMPEDANCE
Definition: foc_utils.h:28
FOCMotor::torque_controller
TorqueControlType torque_controller
parameter determining the torque control type
Definition: FOCMotor.h:163
_normalizeAngle
float _normalizeAngle(float angle)
Definition: foc_utils.cpp:47
FOCMotor::sensor_direction
int sensor_direction
if sensor_direction == Direction::CCW then direction will be flipped to CW
Definition: FOCMotor.h:181
Trapezoid_150
@ Trapezoid_150
Definition: FOCMotor.h:51
_PI_2
#define _PI_2
Definition: foc_utils.h:21
FOCMotor::PID_current_q
PIDController PID_current_q
parameter determining the q current PID config
Definition: FOCMotor.h:167
foc_current
@ foc_current
torque control using dq currents
Definition: FOCMotor.h:41
CurrentSense::getFOCCurrents
DQCurrent_s getFOCCurrents(float angle_el)
Definition: CurrentSense.cpp:37
SinePWM
@ SinePWM
Sinusoidal PWM modulation.
Definition: FOCMotor.h:48
SpaceVectorPWM
@ SpaceVectorPWM
Space vector modulation method.
Definition: FOCMotor.h:49
DQCurrent_s::q
float q
Definition: foc_utils.h:36
DQCurrent_s::d
float d
Definition: foc_utils.h:35
BLDCMotor::loopFOC
void loopFOC() override
Definition: BLDCMotor.cpp:244
PIDController::limit
float limit
Maximum output value.
Definition: pid.h:31
BLDCMotor::Ub
float Ub
Definition: BLDCMotor.h:69
_electricalAngle
float _electricalAngle(float shaft_angle, int pole_pairs)
Definition: foc_utils.cpp:53
FOCMotor::current
DQCurrent_s current
current d and q current measured
Definition: FOCMotor.h:139
dc_current
@ dc_current
Torque control using DC current (one current magnitude)
Definition: FOCMotor.h:40
FOCMotor::current_limit
float current_limit
Current limitting variable - global limit.
Definition: FOCMotor.h:151
FOCMotor::motion_cnt
unsigned int motion_cnt
counting variable for downsampling for move commad
Definition: FOCMotor.h:176
FOCMotor::sensor
Sensor * sensor
Definition: FOCMotor.h:206
_2PI
#define _2PI
Definition: foc_utils.h:23
FOCMotor::P_angle
PIDController P_angle
parameter determining the position PID configuration
Definition: FOCMotor.h:172
CCW
@ CCW
Definition: Sensor.h:9
FOCMotor::voltage
DQVoltage_s voltage
current d and q voltage set to the motor
Definition: FOCMotor.h:138
CurrentSense::getDCCurrent
virtual float getDCCurrent(float angle_el=0)
Definition: CurrentSense.cpp:7
BLDCMotor::move
void move(float target=NOT_SET) override
Definition: BLDCMotor.cpp:295
BLDCMotor::driver
BLDCDriver * driver
Definition: BLDCMotor.h:37
_PI_6
#define _PI_6
Definition: foc_utils.h:25
FOCMotor::modulation_centered
int8_t modulation_centered
flag (1) centered modulation around driver limit /2 or (0) pulled to 0
Definition: FOCMotor.h:159
FOCMotor::current_sense
CurrentSense * current_sense
Definition: FOCMotor.h:210
CurrentSense::driverAlign
virtual int driverAlign(BLDCDriver *driver, float voltage)=0
BLDCMotor::init
void init() override
Definition: BLDCMotor.cpp:26
Direction
Direction
Definition: Sensor.h:7
FOCMotor::controller
MotionControlType controller
parameter determining the control loop to be used
Definition: FOCMotor.h:164
_ACTIVE
#define _ACTIVE
Definition: foc_utils.h:30
FOCMotor::pole_pairs
int pole_pairs
motor pole pairs number
Definition: FOCMotor.h:147
FOCMotor::monitor_port
Print * monitor_port
Serial terminal variable if provided.
Definition: FOCMotor.h:213
_micros
unsigned long _micros()
Definition: time_utils.cpp:21
FOCMotor::LPF_current_q
LowPassFilter LPF_current_q
parameter determining the current Low pass filter configuration
Definition: FOCMotor.h:169
FOCMotor::voltage_sensor_align
float voltage_sensor_align
sensor and motor align voltage parameter
Definition: FOCMotor.h:142
BLDCMotor::BLDCMotor
BLDCMotor(int pp, float R=NOT_SET)
Definition: BLDCMotor.cpp:6
FOCMotor::PID_velocity
PIDController PID_velocity
parameter determining the velocity PID configuration
Definition: FOCMotor.h:171
_SQRT3
#define _SQRT3
Definition: foc_utils.h:15
_cos
float _cos(float a)
Definition: foc_utils.cpp:39
DQVoltage_s::q
float q
Definition: foc_utils.h:49
BLDCMotor::linkDriver
void linkDriver(BLDCDriver *driver)
Definition: BLDCMotor.cpp:21
FOCMotor::velocity_limit
float velocity_limit
Velocity limitting variable - global limit.
Definition: FOCMotor.h:152
FOCMotor::motion_downsample
unsigned int motion_downsample
parameter defining the ratio of downsampling for move commad
Definition: FOCMotor.h:175
angle_openloop
@ angle_openloop
Definition: FOCMotor.h:32
FOCMotor::velocity_index_search
float velocity_index_search
target velocity for index search
Definition: FOCMotor.h:143
BLDCMotor::Ualpha
float Ualpha
Definition: BLDCMotor.h:70
BLDCDriver::disable
virtual void disable()=0
BLDCDriver::enable
virtual void enable()=0
_sign
#define _sign(a)
Definition: foc_utils.h:7
BLDCMotor::Uc
float Uc
Current phase voltages Ua,Ub and Uc set to motor.
Definition: BLDCMotor.h:69
_3PI_2
#define _3PI_2
Definition: foc_utils.h:24
BLDCDriver::setPhaseState
virtual void setPhaseState(int sa, int sb, int sc)=0
FOCMotor::shaftVelocity
float shaftVelocity()
Definition: FOCMotor.cpp:62
Sensor::getAngle
virtual float getAngle()=0
FOCMotor::shaft_angle_sp
float shaft_angle_sp
current target angle
Definition: FOCMotor.h:137