SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
FOCMotor.h
Go to the documentation of this file.
1#ifndef FOCMOTOR_H
2#define FOCMOTOR_H
3
4#include "Arduino.h"
5#include "Sensor.h"
6#include "CurrentSense.h"
7
8#include "../time_utils.h"
9#include "../foc_utils.h"
10#include "../defaults.h"
11#include "../pid.h"
12#include "../lowpass_filter.h"
13
14#define MOT_ERR "ERR-MOT:"
15#define MOT_WARN "WARN-MOT:"
16#define MOT_DEBUG "MOT:"
17
18#ifndef SIMPLEFOC_DISABLE_DEBUG
19#define SIMPLEFOC_MOTOR_WARN(msg, ...) \
20 SimpleFOCDebug::print(MOT_WARN); \
21 SIMPLEFOC_DEBUG(msg, ##__VA_ARGS__)
22
23#define SIMPLEFOC_MOTOR_ERROR(msg, ...) \
24 SimpleFOCDebug::print(MOT_ERR); \
25 SIMPLEFOC_DEBUG(msg, ##__VA_ARGS__)
26
27#define SIMPLEFOC_MOTOR_DEBUG(msg, ...) \
28 SimpleFOCDebug::print(MOT_DEBUG); \
29 SIMPLEFOC_DEBUG(msg, ##__VA_ARGS__)
30
31#else
32#define SIMPLEFOC_MOTOR_DEBUG(msg, ...)
33#define SIMPLEFOC_MOTOR_ERROR(msg, ...)
34#define SIMPLEFOC_MOTOR_WARN(msg, ...)
35#endif
36
37// monitoring bitmap
38#define _MON_TARGET 0b1000000 // monitor target value
39#define _MON_VOLT_Q 0b0100000 // monitor voltage q value
40#define _MON_VOLT_D 0b0010000 // monitor voltage d value
41#define _MON_CURR_Q 0b0001000 // monitor current q value - if measured
42#define _MON_CURR_D 0b0000100 // monitor current d value - if measured
43#define _MON_VEL 0b0000010 // monitor velocity value
44#define _MON_ANGLE 0b0000001 // monitor angle value
45
46/**
47 * Motion control type
48 */
49enum MotionControlType : uint8_t {
50 torque = 0x00, //!< Torque control
51 velocity = 0x01, //!< Velocity motion control
52 angle = 0x02, //!< Position/angle motion control
55 angle_nocascade = 0x05, //!< Position/angle motion control without velocity cascade
56 custom = 0x06 //!< Custom control method - control method added by user
57};
58
59/**
60 * Motiron control type
61 */
62enum TorqueControlType : uint8_t {
63 voltage = 0x00, //!< Torque control using voltage
64 dc_current = 0x01, //!< Torque control using DC current (one current magnitude)
65 foc_current = 0x02, //!< torque control using dq currents
66 estimated_current = 0x03 //!< torque control using estimated current (provided motor parameters)
67};
68
69/**
70 * FOC modulation type
71 */
72enum FOCModulationType : uint8_t {
73 SinePWM = 0x00, //!< Sinusoidal PWM modulation
74 SpaceVectorPWM = 0x01, //!< Space vector modulation method
77};
78
79
80
81enum FOCMotorStatus : uint8_t {
82 motor_uninitialized = 0x00, //!< Motor is not yet initialized
83 motor_initializing = 0x01, //!< Motor intiialization is in progress
84 motor_uncalibrated = 0x02, //!< Motor is initialized, but not calibrated (open loop possible)
85 motor_calibrating = 0x03, //!< Motor calibration in progress
86 motor_ready = 0x04, //!< Motor is initialized and calibrated (closed loop possible)
87 motor_error = 0x08, //!< Motor is in error state (recoverable, e.g. overcurrent protection active)
88 motor_calib_failed = 0x0E, //!< Motor calibration failed (possibly recoverable)
89 motor_init_failed = 0x0F, //!< Motor initialization failed (not recoverable)
90};
91
92
93
94/**
95 Generic motor class
96*/
98{
99 public:
100 /**
101 * Default constructor - setting all variabels to default values
102 */
103 FOCMotor();
104
105
106 // Methods that need to be implemented, defining the FOCMotor interface
107
108 /** Motor hardware init function */
109 virtual int init() = 0;
110 /** Motor disable function */
111 virtual void disable()=0;
112 /** Motor enable function */
113 virtual void enable()=0;
114
115 /**
116 * Method using FOC to set Uq to the motor at the optimal angle
117 * Heart of the FOC algorithm
118 *
119 * @param Uq Current voltage in q axis to set to the motor
120 * @param Ud Current voltage in d axis to set to the motor
121 * @param angle_el current electrical angle of the motor
122 */
123 virtual void setPhaseVoltage(float Uq, float Ud, float angle_el)=0;
124
125 /**
126 * Estimation of the Back EMF voltage
127 *
128 * @param velocity - current shaft velocity
129 */
130 virtual float estimateBEMF(float velocity){return 0.0f;};
131
132 // Methods that have a default behavior but can be overriden if needed
133
134 /**
135 * Function initializing FOC algorithm
136 * and aligning sensor's and motors' zero position
137 *
138 * - If zero_electric_offset parameter is set the alignment procedure is skipped
139 */
140 virtual int initFOC();
141
142 /**
143 * Function running FOC algorithm in real-time
144 * it calculates the gets motor angle and sets the appropriate voltages
145 * to the phase pwm signals
146 * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us
147 */
148 virtual void loopFOC();
149
150 /**
151 * Function executing the control loops set by the controller.
152 *
153 * @param target Either voltage, angle or velocity based on the motor.controller
154 * If it is not set the motor will use the target set in its variable motor.target
155 *
156 * This function doesn't need to be run upon each loop execution - depends of the use case
157 */
158 virtual void move(float target = NOT_SET);
159
160 /**
161 * Function linking a motor and a sensor
162 *
163 * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity
164 */
165 void linkSensor(Sensor* sensor);
166
167 /**
168 * Function linking a motor and current sensing
169 *
170 * @param current_sense CurrentSense class wrapper for the FOC algorihtm to read the motor current measurements
171 */
173
174
175 // State calculation methods
176 /** Shaft angle calculation in radians [rad] */
177 float shaftAngle();
178 /**
179 * Shaft angle calculation function in radian per second [rad/s]
180 * It implements low pass filtering
181 */
182 float shaftVelocity();
183
184 /**
185 * Electrical angle calculation
186 */
187 float electricalAngle();
188
189
190 /**
191 * Measure resistance and inductance of a motor and print results to debug.
192 * If a sensor is available, an estimate of zero electric angle will be reported too.
193 * @param voltage The voltage applied to the motor
194 * @param correction_factor Is 1.5 for 3 phase motors, because we measure over a series-parallel connection. TODO: what about 2 phase motors?
195 * @returns 0 for success, >0 for failure
196 */
197 int characteriseMotor(float voltage, float correction_factor);
198
199 /**
200 * Auto-tune the current controller PID parameters based on desired bandwidth.
201 * Uses a simple method that assumes a first order system and requires knowledge of
202 * the motor phase resistance and inductance (if not set, the characteriseMotor function can be used).
203 *
204 * @param bandwidth Desired closed-loop bandwidth in Hz.
205 * @returns returns 0 for success, >0 for failure
206 */
207 int tuneCurrentController(float bandwidth);
208
209 // state variables
210 float target; //!< current target value - depends of the controller
211 float feed_forward_velocity = 0.0f; //!< current feed forward velocity
212 float shaft_angle;//!< current motor angle
213 float electrical_angle;//!< current electrical angle
214 float shaft_velocity;//!< current motor velocity
215 float current_sp;//!< target current ( q current )
216 float shaft_velocity_sp;//!< current target velocity
217 float shaft_angle_sp;//!< current target angle
218 DQVoltage_s voltage;//!< current d and q voltage set to the motor
219 DQCurrent_s current;//!< current d and q current measured
220 float voltage_bemf; //!< estimated backemf voltage (if provided KV constant)
221 float Ualpha, Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform
222
223 DQCurrent_s feed_forward_current;//!< current d and q current measured
224 DQVoltage_s feed_forward_voltage;//!< current d and q voltage set to the motor
225
226 // motor configuration parameters
227 float voltage_sensor_align;//!< sensor and motor align voltage parameter
228 float velocity_index_search;//!< target velocity for index search
229
230 // motor physical parameters
231 float phase_resistance; //!< motor phase resistance
232 int pole_pairs;//!< motor pole pairs number
233 float KV_rating; //!< motor KV rating
234 float phase_inductance; //!< motor phase inductance q axis - FOR BACKWARDS COMPATIBILITY
235 DQ_s axis_inductance{NOT_SET, NOT_SET}; //!< motor direct axis phase inductance
236
237 // limiting variables
238 float voltage_limit; //!< Voltage limiting variable - global limit
239 float current_limit; //!< Current limiting variable - global limit
240 float velocity_limit; //!< Velocity limiting variable - global limit
241
242 // motor status vairables
243 int8_t enabled = 0;//!< enabled or disabled motor flag
245
246 // pwm modulation related variables
247 FOCModulationType foc_modulation;//!< parameter determining modulation algorithm
248 int8_t modulation_centered = 1;//!< flag (1) centered modulation around driver limit /2 or (0) pulled to 0
249
250
251 // configuration structures
252 TorqueControlType torque_controller; //!< parameter determining the torque control type
253 MotionControlType controller; //!< parameter determining the control loop to be used
254
255 // controllers and low pass filters
258 LowPassFilter LPF_current_q{DEF_CURR_FILTER_Tf};//!< parameter determining the current Low pass filter configuration
259 LowPassFilter LPF_current_d{DEF_CURR_FILTER_Tf};//!< parameter determining the current Low pass filter configuration
261 PIDController P_angle{DEF_P_ANGLE_P,0,0,0,DEF_VEL_LIM}; //!< parameter determining the position PID configuration
262 LowPassFilter LPF_velocity{DEF_VEL_FILTER_Tf};//!< parameter determining the velocity Low pass filter configuration
263 LowPassFilter LPF_angle{0.0};//!< parameter determining the angle low pass filter configuration
264 unsigned int motion_downsample = DEF_MOTION_DOWNSMAPLE; //!< parameter defining the ratio of downsampling for move commad
265 unsigned int motion_cnt = 0; //!< counting variable for downsampling for move commad
266
267 // sensor related variabels
268 float sensor_offset; //!< user defined sensor zero offset
269 float zero_electric_angle = NOT_SET;//!< absolute zero electric angle - if available
270 Direction sensor_direction = Direction::UNKNOWN; //!< default is CW. if sensor_direction == Direction::CCW then direction will be flipped compared to CW. Set to UNKNOWN to set by calibration
271 bool pp_check_result = false; //!< the result of the PP check, if run during loopFOC
272
273 /**
274 * Function providing BLDCMotor class with the
275 * Serial interface and enabling monitoring mode
276 *
277 * @param serial Monitoring Serial class reference
278 */
279 void useMonitoring(Print &serial);
280
281 /**
282 * Utility function intended to be used with serial plotter to monitor motor variables
283 * significantly slowing the execution down!!!!
284 */
285 void monitor();
286 unsigned int monitor_downsample = DEF_MON_DOWNSMAPLE; //!< show monitor outputs each monitor_downsample calls
287 char monitor_start_char = '\0'; //!< monitor starting character
288 char monitor_end_char = '\0'; //!< monitor outputs ending character
289 char monitor_separator = '\t'; //!< monitor outputs separation character
290 unsigned int monitor_decimals = 4; //!< monitor outputs decimal places
291 // initial monitoring will display target, voltage, velocity and angle
292 uint8_t monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VEL | _MON_ANGLE; //!< Bit array holding the map of variables the user wants to monitor
293
294 /**
295 * Sensor link:
296 * - Encoder
297 * - MagneticSensor*
298 * - HallSensor
299 */
301 //!< CurrentSense link
303
304 // monitoring functions
305 Print* monitor_port; //!< Serial terminal variable if provided
306
307 //!< time between two loopFOC executions in microseconds
308 uint32_t loopfoc_time_us = 0; //!< filtered loop times
309 uint32_t move_time_us = 0; // filtered motion control times
310
311 /**
312 * Update limit values in controllers when changed
313 * @param new_velocity_limit - new velocity limit value
314 *
315 * @note Updates velocity limit in:
316 * - motor.velocity_limit
317 * - motor.P_angle.limit
318 */
319 void updateVelocityLimit(float new_velocity_limit);
320 /**
321 * Update limit values in controllers when changed
322 * @param new_current_limit - new current limit value
323 *
324 * @note Updates current limit in:
325 * - motor.current_limit
326 * - motor.PID_velocity.limit (if current control)
327 */
328 void updateCurrentLimit(float new_current_limit);
329 /**
330 * Update limit values in controllers when changed
331 * @param new_voltage_limit - new voltage limit value
332 *
333 * @note Updates voltage limit in:
334 * - motor.voltage_limit
335 * - motor.PID_current_q.limit
336 * - motor.PID_current_d.limit
337 * - motor.PID_velocity.limit (if voltage control)
338 */
339 void updateVoltageLimit(float new_voltage_limit);
340
341 /**
342 * Update torque control type and related controller limit values
343 * @param new_torque_controller - new torque control type
344 *
345 * @note Updates motor.torque_controller and motor.PID_velocity.limit
346 */
347 void updateTorqueControlType(TorqueControlType new_torque_controller);
348 /**
349 * Update motion control type and related target values
350 * @param new_motion_controller - new motion control type
351 *
352 * @note Updates the target value based on the new controller type
353 * - if velocity control: target is set to 0rad/s
354 * - if angle control: target is set to the current shaft_angle
355 * - if torque control: target is set to 0V or 0A depending on torque control type
356 */
357 void updateMotionControlType(MotionControlType new_motion_controller);
358
359 // Open loop motion control
360 /**
361 * Function (iterative) generating open loop movement for target velocity
362 * it uses voltage_limit variable
363 *
364 * @param target_velocity - rad/s
365 */
366 float velocityOpenloop(float target_velocity);
367 /**
368 * Function (iterative) generating open loop movement towards the target angle
369 * it uses voltage_limit and velocity_limit variables
370 *
371 * @param target_angle - rad
372 */
373 float angleOpenloop(float target_angle);
374
375
376 /**
377 * Function setting a custom motion control method defined by the user
378 * @note the custom control method has to be defined by the user and should follow the signature: float controlMethod(FOCMotor* motor)
379 * @param controlMethod - pointer to the custom control method function defined by the user
380 */
381 void linkCustomMotionControl(float (*controlMethod)(FOCMotor* motor)){
382 customMotionControlCallback = controlMethod;
383 }
384
385 protected:
386
387 /**
388 * Function udating loop time measurement
389 * time between two loopFOC executions in microseconds
390 * It filters the value using low pass filtering alpha = 0.1
391 * @note - using _micros() function - be aware of its overflow every ~70 minutes
392 */
396
400
401 /** Sensor alignment to electrical 0 angle of the motor */
402 int alignSensor();
403 /** Current sense and motor phase alignment */
404 int alignCurrentSense();
405 /** Motor and sensor alignment to the sensors absolute 0 angle */
406 int absoluteZeroSearch();
407
408 uint32_t last_loopfoc_timestamp_us = 0; //!< timestamp of the last loopFOC execution in microseconds
409 uint32_t last_loopfoc_time_us = 0; //!< last elapsed time of loopFOC in microseconds
410 uint32_t last_move_timestamp_us = 0; //!< timestamp of the last move execution in microseconds
411 uint32_t last_move_time_us = 0; //!< last elapsed time of move in microseconds
412 private:
413 // monitor counting variable
414 unsigned int monitor_cnt = 0 ; //!< counting variable
415
416 // time measuring function
417 // It filters the value using low pass filtering alpha = 0.1
418 void updateTime(uint32_t& elapsed_time_filetered, uint32_t& elapsed_time, uint32_t& last_timestamp_us, float alpha = 0.1f){
419 uint32_t now = _micros();
420 elapsed_time = now - last_timestamp_us;
421 elapsed_time_filetered = (1-alpha) * elapsed_time_filetered + alpha * elapsed_time;
422 last_timestamp_us = now;
423 }
424
425 // open loop variables
426 uint32_t open_loop_timestamp;
427
428 // function pointer for custom control method
429 float (*customMotionControlCallback)(FOCMotor* motor) = nullptr;
430
431};
432
433
434#endif
#define _MON_ANGLE
Definition FOCMotor.h:44
MotionControlType
Definition FOCMotor.h:49
@ velocity_openloop
Definition FOCMotor.h:53
@ velocity
Velocity motion control.
Definition FOCMotor.h:51
@ angle_openloop
Definition FOCMotor.h:54
@ custom
Custom control method - control method added by user.
Definition FOCMotor.h:56
@ torque
Torque control.
Definition FOCMotor.h:50
@ angle_nocascade
Position/angle motion control without velocity cascade.
Definition FOCMotor.h:55
@ angle
Position/angle motion control.
Definition FOCMotor.h:52
#define _MON_VEL
Definition FOCMotor.h:43
#define _MON_TARGET
Definition FOCMotor.h:38
FOCModulationType
Definition FOCMotor.h:72
@ Trapezoid_120
Definition FOCMotor.h:75
@ SpaceVectorPWM
Space vector modulation method.
Definition FOCMotor.h:74
@ Trapezoid_150
Definition FOCMotor.h:76
@ SinePWM
Sinusoidal PWM modulation.
Definition FOCMotor.h:73
FOCMotorStatus
Definition FOCMotor.h:81
@ motor_ready
Motor is initialized and calibrated (closed loop possible)
Definition FOCMotor.h:86
@ motor_uncalibrated
Motor is initialized, but not calibrated (open loop possible)
Definition FOCMotor.h:84
@ motor_initializing
Motor intiialization is in progress.
Definition FOCMotor.h:83
@ motor_uninitialized
Motor is not yet initialized.
Definition FOCMotor.h:82
@ motor_calibrating
Motor calibration in progress.
Definition FOCMotor.h:85
@ motor_init_failed
Motor initialization failed (not recoverable)
Definition FOCMotor.h:89
@ motor_error
Motor is in error state (recoverable, e.g. overcurrent protection active)
Definition FOCMotor.h:87
@ motor_calib_failed
Motor calibration failed (possibly recoverable)
Definition FOCMotor.h:88
#define _MON_VOLT_Q
Definition FOCMotor.h:39
TorqueControlType
Definition FOCMotor.h:62
@ estimated_current
torque control using estimated current (provided motor parameters)
Definition FOCMotor.h:66
@ voltage
Torque control using voltage.
Definition FOCMotor.h:63
@ dc_current
Torque control using DC current (one current magnitude)
Definition FOCMotor.h:64
@ foc_current
torque control using dq currents
Definition FOCMotor.h:65
Direction
Definition Sensor.h:9
@ UNKNOWN
Definition Sensor.h:12
int characteriseMotor(float voltage, float correction_factor)
Definition FOCMotor.cpp:96
int8_t enabled
enabled or disabled motor flag
Definition FOCMotor.h:243
void updateCurrentLimit(float new_current_limit)
Definition FOCMotor.cpp:453
void updateLoopFOCTime()
Definition FOCMotor.h:393
int absoluteZeroSearch()
Definition FOCMotor.cpp:930
void linkSensor(Sensor *sensor)
Definition FOCMotor.cpp:53
int8_t modulation_centered
flag (1) centered modulation around driver limit /2 or (0) pulled to 0
Definition FOCMotor.h:248
DQ_s axis_inductance
motor direct axis phase inductance
Definition FOCMotor.h:235
void monitor()
Definition FOCMotor.cpp:321
void useMonitoring(Print &serial)
Definition FOCMotor.cpp:87
char monitor_separator
monitor outputs separation character
Definition FOCMotor.h:289
uint32_t last_loopfoc_timestamp_us
timestamp of the last loopFOC execution in microseconds
Definition FOCMotor.h:408
int alignSensor()
Definition FOCMotor.cpp:847
virtual void enable()=0
PIDController PID_current_q
parameter determining the q current PID config
Definition FOCMotor.h:256
float Ualpha
Definition FOCMotor.h:221
virtual void setPhaseVoltage(float Uq, float Ud, float angle_el)=0
void updateVoltageLimit(float new_voltage_limit)
Definition FOCMotor.cpp:466
float sensor_offset
user defined sensor zero offset
Definition FOCMotor.h:268
LowPassFilter LPF_angle
parameter determining the angle low pass filter configuration
Definition FOCMotor.h:263
DQVoltage_s voltage
current d and q voltage set to the motor
Definition FOCMotor.h:218
virtual int init()=0
LowPassFilter LPF_velocity
parameter determining the velocity Low pass filter configuration
Definition FOCMotor.h:262
uint8_t monitor_variables
Bit array holding the map of variables the user wants to monitor.
Definition FOCMotor.h:292
MotionControlType controller
parameter determining the control loop to be used
Definition FOCMotor.h:253
float phase_resistance
motor phase resistance
Definition FOCMotor.h:231
uint32_t loopfoc_time_us
filtered loop times
Definition FOCMotor.h:308
void updateTorqueControlType(TorqueControlType new_torque_controller)
Definition FOCMotor.cpp:480
virtual int initFOC()
Definition FOCMotor.cpp:774
float velocityOpenloop(float target_velocity)
Definition FOCMotor.cpp:389
uint32_t last_move_time_us
last elapsed time of move in microseconds
Definition FOCMotor.h:411
float angleOpenloop(float target_angle)
Definition FOCMotor.cpp:414
PIDController PID_current_d
parameter determining the d current PID config
Definition FOCMotor.h:257
Sensor * sensor
CurrentSense link.
Definition FOCMotor.h:300
DQVoltage_s feed_forward_voltage
current d and q voltage set to the motor
Definition FOCMotor.h:224
CurrentSense * current_sense
Definition FOCMotor.h:302
void linkCurrentSense(CurrentSense *current_sense)
Definition FOCMotor.cpp:60
virtual void move(float target=NOT_SET)
Definition FOCMotor.cpp:673
uint32_t last_loopfoc_time_us
last elapsed time of loopFOC in microseconds
Definition FOCMotor.h:409
float current_sp
target current ( q current )
Definition FOCMotor.h:215
uint32_t last_move_timestamp_us
timestamp of the last move execution in microseconds
Definition FOCMotor.h:410
uint32_t move_time_us
Definition FOCMotor.h:309
float voltage_limit
Voltage limiting variable - global limit.
Definition FOCMotor.h:238
float velocity_limit
Velocity limiting variable - global limit.
Definition FOCMotor.h:240
float electricalAngle()
Definition FOCMotor.cpp:77
bool pp_check_result
the result of the PP check, if run during loopFOC
Definition FOCMotor.h:271
PIDController P_angle
parameter determining the position PID configuration
Definition FOCMotor.h:261
unsigned int monitor_decimals
monitor outputs decimal places
Definition FOCMotor.h:290
unsigned int monitor_downsample
show monitor outputs each monitor_downsample calls
Definition FOCMotor.h:286
virtual float estimateBEMF(float velocity)
Definition FOCMotor.h:130
LowPassFilter LPF_current_q
parameter determining the current Low pass filter configuration
Definition FOCMotor.h:258
unsigned int motion_cnt
counting variable for downsampling for move commad
Definition FOCMotor.h:265
char monitor_end_char
monitor outputs ending character
Definition FOCMotor.h:288
Print * monitor_port
Serial terminal variable if provided.
Definition FOCMotor.h:305
FOCMotorStatus motor_status
motor status
Definition FOCMotor.h:244
float velocity_index_search
target velocity for index search
Definition FOCMotor.h:228
float feed_forward_velocity
current feed forward velocity
Definition FOCMotor.h:211
char monitor_start_char
monitor starting character
Definition FOCMotor.h:287
virtual void loopFOC()
Definition FOCMotor.cpp:580
LowPassFilter LPF_current_d
parameter determining the current Low pass filter configuration
Definition FOCMotor.h:259
float Ubeta
Phase voltages U alpha and U beta used for inverse Park and Clarke transform.
Definition FOCMotor.h:221
int alignCurrentSense()
Definition FOCMotor.cpp:827
float shaft_angle_sp
current target angle
Definition FOCMotor.h:217
float shaft_velocity
current motor velocity
Definition FOCMotor.h:214
float shaftVelocity()
Definition FOCMotor.cpp:71
float shaftAngle()
Definition FOCMotor.cpp:65
float KV_rating
motor KV rating
Definition FOCMotor.h:233
float voltage_bemf
estimated backemf voltage (if provided KV constant)
Definition FOCMotor.h:220
float shaft_angle
current motor angle
Definition FOCMotor.h:212
int tuneCurrentController(float bandwidth)
Definition FOCMotor.cpp:538
float voltage_sensor_align
sensor and motor align voltage parameter
Definition FOCMotor.h:227
Direction sensor_direction
default is CW. if sensor_direction == Direction::CCW then direction will be flipped compared to CW....
Definition FOCMotor.h:270
void updateMotionControlTime()
Definition FOCMotor.h:397
float target
current target value - depends of the controller
Definition FOCMotor.h:210
float current_limit
Current limiting variable - global limit.
Definition FOCMotor.h:239
float electrical_angle
current electrical angle
Definition FOCMotor.h:213
DQCurrent_s feed_forward_current
current d and q current measured
Definition FOCMotor.h:223
void linkCustomMotionControl(float(*controlMethod)(FOCMotor *motor))
Definition FOCMotor.h:381
TorqueControlType torque_controller
parameter determining the torque control type
Definition FOCMotor.h:252
PIDController PID_velocity
parameter determining the velocity PID configuration
Definition FOCMotor.h:260
float phase_inductance
motor phase inductance q axis - FOR BACKWARDS COMPATIBILITY
Definition FOCMotor.h:234
float zero_electric_angle
absolute zero electric angle - if available
Definition FOCMotor.h:269
DQCurrent_s current
current d and q current measured
Definition FOCMotor.h:219
virtual void disable()=0
int pole_pairs
motor pole pairs number
Definition FOCMotor.h:232
void updateVelocityLimit(float new_velocity_limit)
Definition FOCMotor.cpp:446
FOCModulationType foc_modulation
parameter determining modulation algorithm
Definition FOCMotor.h:247
unsigned int motion_downsample
parameter defining the ratio of downsampling for move commad
Definition FOCMotor.h:264
void updateMotionControlType(MotionControlType new_motion_controller)
Definition FOCMotor.cpp:495
float shaft_velocity_sp
current target velocity
Definition FOCMotor.h:216
#define DEF_MON_DOWNSMAPLE
default monitor downsample
Definition defaults.h:36
#define DEF_PID_VEL_RAMP
default PID controller voltage ramp value
Definition defaults.h:9
#define DEF_PID_CURR_I
default PID controller I value
Definition defaults.h:25
#define DEF_PID_VEL_D
default PID controller D value
Definition defaults.h:8
#define DEF_PID_VEL_I
default PID controller I value
Definition defaults.h:7
#define DEF_VEL_FILTER_Tf
default velocity filter time constant
Definition defaults.h:48
#define DEF_VEL_LIM
angle velocity limit default
Definition defaults.h:41
#define DEF_PID_CURR_RAMP
default PID controller voltage ramp value
Definition defaults.h:27
#define DEF_PID_VEL_LIMIT
default PID controller voltage limit
Definition defaults.h:10
#define DEF_PID_CURR_P
default PID controller P value
Definition defaults.h:24
#define DEF_PID_CURR_D
default PID controller D value
Definition defaults.h:26
#define DEF_MOTION_DOWNSMAPLE
default motion downsample - disable
Definition defaults.h:37
#define DEF_POWER_SUPPLY
default power supply voltage
Definition defaults.h:4
#define DEF_PID_VEL_P
default PID controller P value
Definition defaults.h:6
#define DEF_CURR_FILTER_Tf
default currnet filter time constant
Definition defaults.h:30
#define DEF_P_ANGLE_P
default P controller P value
Definition defaults.h:40
#define NOT_SET
Definition foc_utils.h:34
unsigned long _micros()