Skip to content

Commit 29efc20

Browse files
committed
TYPO removed a lot typos
1 parent c7405df commit 29efc20

23 files changed

+778
-147
lines changed

README.md

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,13 @@
44
[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT)
55
[![arduino-library-badge](https://www.ardu-badge.com/badge/Simple%20FOC.svg?)](https://www.ardu-badge.com/badge/Simple%20FOC.svg)
66

7-
This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experiemtation and modification!
7+
This is the minimal Arduino example of the [Simple FOC](https://github.com/askuric/Arduino-FOC) arduino library intended for mostly for easier experimentation and modification!
88

99
### Minimal repository structure
1010
```shell
1111
├───arduino_foc_minimal_encoder # Arduino minimal code for running a motor with Encoder
1212
13-
└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magentic sensor
13+
└───arduino_foc_minimal_magnetic # Arduino minimal code for running a motor with magnetic sensor
1414
# AS5048/47
1515
```
1616

@@ -32,17 +32,17 @@ Control loop type:
3232
- C2 - voltage control
3333
3434
Initial parameters:
35-
PI velocity P: 0.20, I: 20.00, Low passs filter Tf: 0.0000
35+
PI velocity P: 0.20, I: 20.00, Low pass filter Tf: 0.0000
3636
```
3737

3838
### Installation
3939
For those willing to experiment and to modify the code I suggest using the [minimal version](https://github.com/askuric/Arduino-FOC/tree/minimal) of the code.
40-
> This code is completely indepenedet and you can run it as any other Arduino Schetch without the need for any libraries.
40+
> This code is completely independent and you can run it as any other Arduino Sketch without the need for any libraries.
4141
42-
#### Github webiste downlaod
42+
#### Github website download
4343
- Make sure you are in [minimal branch](https://github.com/askuric/Arduino-FOC/tree/minimal)
44-
- Downlaod the code by clicking on the `Clone or Download > Download ZIP`.
45-
- Unzip it and open the schetch in Arduino IDE.
44+
- Download the code by clicking on the `Clone or Download > Download ZIP`.
45+
- Unzip it and open the sketch in Arduino IDE.
4646

4747
#### Using terminal
4848
- Open the terminal:
@@ -60,5 +60,5 @@ Find out more information about the Arduino SimpleFOC project in [docs website](
6060
Branch | Description | Status
6161
------------ | ------------- | ------------
6262
[master](https://github.com/askuric/Arduino-FOC) | Stable and tested library version | ![Library Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Compile/badge.svg)
63-
[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Developement library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev)
63+
[dev](https://github.com/askuric/Arduino-FOC/tree/dev) | Development library version | ![Library Dev Compile](https://github.com/askuric/Arduino-FOC/workflows/Library%20Dev%20Compile/badge.svg?branch=dev)
6464
[minimal](https://github.com/askuric/Arduino-FOC/tree/minimal) | Minimal Arduino example with integrated library | ![MinimalBuild](https://github.com/askuric/Arduino-FOC/workflows/MinimalBuild/badge.svg?branch=minimal)

arduino_foc_minimal_encoder/BLDCMotor.cpp

Lines changed: 52 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,10 @@
44
// - phA, phB, phC - motor A,B,C phase pwm pins
55
// - pp - pole pair number
66
// - cpr - counts per rotation number (cpm=ppm*4)
7-
// - enable pin - (optionl input)
7+
// - enable pin - (optional input)
88
BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
99
{
10-
// Pin intialization
10+
// Pin initialization
1111
pwmA = phA;
1212
pwmB = phB;
1313
pwmC = phC;
@@ -16,7 +16,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
1616
// enable_pin pin
1717
enable_pin = en;
1818

19-
// Power supply woltage
19+
// Power supply voltage
2020
voltage_power_supply = DEF_POWER_SUPPLY;
2121

2222
// Velocity loop config
@@ -61,7 +61,7 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
6161

6262
// init hardware pins
6363
void BLDCMotor::init() {
64-
if(debugger) debugger->println("DEBUG: Initilaise the motor pins.");
64+
if(debugger) debugger->println("DEBUG: Initialize the motor pins.");
6565
// PWM pins
6666
pinMode(pwmA, OUTPUT);
6767
pinMode(pwmB, OUTPUT);
@@ -118,7 +118,7 @@ void BLDCMotor::linkSensor(Sensor* _sensor) {
118118
// Encoder alignment to electrical 0 angle
119119
int BLDCMotor::alignSensor() {
120120
if(debugger) debugger->println("DEBUG: Align the sensor's and motor electrical 0 angle.");
121-
// align the electircal phases of the motor and sensor
121+
// align the electrical phases of the motor and sensor
122122
setPwm(pwmA, voltage_power_supply/2.0);
123123
setPwm(pwmB,0);
124124
setPwm(pwmC,0);
@@ -159,7 +159,7 @@ int BLDCMotor::absoluteZeroAlign() {
159159
// disable motor
160160
setPhaseVoltage(0,0);
161161

162-
// align absoulute zero if it has been found
162+
// align absolute zero if it has been found
163163
if(!sensor->needsAbsoluteZeroSearch()){
164164
// align the sensor with the absolute zero
165165
float zero_offset = sensor->initAbsoluteZero();
@@ -182,7 +182,7 @@ float BLDCMotor::shaftVelocity() {
182182
float Ts = (_micros() - LPF_velocity.timestamp) * 1e-6;
183183
// quick fix for strange cases (micros overflow)
184184
if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
185-
// calculate the fitering
185+
// calculate the filtering
186186
float alpha = LPF_velocity.Tf/(LPF_velocity.Tf + Ts);
187187
float vel = alpha*LPF_velocity.prev + (1-alpha)*sensor->getVelocity();
188188
// save the variables
@@ -197,7 +197,7 @@ float BLDCMotor::electricAngle(float shaftAngle) {
197197
}
198198

199199
/**
200-
FOC funcitons
200+
FOC functions
201201
*/
202202

203203
// FOC initialization function
@@ -214,14 +214,14 @@ int BLDCMotor::initFOC() {
214214
void BLDCMotor::loopFOC() {
215215
// shaft angle
216216
shaft_angle = shaftAngle();
217-
// set the phase voltage - FOC heart funciton :)
217+
// set the phase voltage - FOC heart function :)
218218
setPhaseVoltage(voltage_q, electricAngle(shaft_angle));
219219
}
220220

221-
// Iterative funciton running outer loop of the FOC algorithm
222-
// Bahvior of this funciton is determined by the motor.controller variable
223-
// It runs either angle, veloctiy or voltage loop
224-
// - needs to be called iteratively it is asynchronious function
221+
// Iterative function running outer loop of the FOC algorithm
222+
// Behavior of this function is determined by the motor.controller variable
223+
// It runs either angle, velocity or voltage loop
224+
// - needs to be called iteratively it is asynchronous function
225225
void BLDCMotor::move(float target) {
226226
// get angular velocity
227227
shaft_velocity = shaftVelocity();
@@ -238,7 +238,7 @@ void BLDCMotor::move(float target) {
238238
break;
239239
case ControlType::velocity:
240240
// velocity set point
241-
// inlcude velocity loop
241+
// include velocity loop
242242
shaft_velocity_sp = target;
243243
voltage_q = velocityPI(shaft_velocity_sp - shaft_velocity);
244244
break;
@@ -250,16 +250,16 @@ void BLDCMotor::move(float target) {
250250
void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
251251

252252
// angle normalisation in between 0 and 2pi
253-
// only necessary if using _sin and _cos - approximation funcitons
253+
// only necessary if using _sin and _cos - approximation functions
254254
float angle = normalizeAngle(angle_el + zero_electric_angle);
255255
// Inverse park transform
256-
// regular sin + cos ~300us (no memeory usaage)
256+
// regular sin + cos ~300us (no memory usaage)
257257
// approx _sin + _cos ~110us (400Byte ~ 20% of memory)
258258
// Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq;
259259
// Ubeta = _cos(angle) * Uq; // cos(angle) * Uq;
260260
Ualpha = -_sin(angle) * Uq; // -sin(angle) * Uq;
261261
Ubeta = _cos(angle) * Uq; // cos(angle) * Uq;
262-
262+
263263
// Clarke transform
264264
Ua = Ualpha;
265265
Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta;
@@ -273,32 +273,25 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
273273

274274

275275
// Set voltage to the pwm pin
276-
// - function a bit optimised to get better performance
276+
// - function a bit optimized to get better performance
277277
void BLDCMotor::setPwm(int pinPwm, float U) {
278278
// max value
279279
float U_max = voltage_power_supply/2.0;
280280

281281
// sets the voltage [-U_max,U_max] to pwm [0,255]
282282
// u_pwm = 255 * (U + U_max)/(2*U_max)
283-
// it can be further optimised
283+
// it can be further optimized
284284
// (example U_max = 6 > U_pwm = 127.5 + 21.25*U)
285285
int U_pwm = 127.5 * (U/U_max + 1);
286-
287-
288-
// float U_max = voltage_power_supply;
289-
// // sets the voltage [0,12V(U_max)] to pwm [0,255]
290-
// // - U_max you can set in header file - default 12V
291-
// // - support for HMBGC controller
292-
// int U_pwm = 255.0 * (float)U / (float)U_max;
293-
286+
294287
// limit the values between 0 and 255
295288
U_pwm = (U_pwm < 0) ? 0 : (U_pwm >= 255) ? 255 : U_pwm;
296289

297290
analogWrite(pinPwm, U_pwm);
298291
}
299292

300293
/**
301-
Utility funcitons
294+
Utility functions
302295
*/
303296
// normalizing radian angle to [0,2PI]
304297
float BLDCMotor::normalizeAngle(float angle){
@@ -321,7 +314,7 @@ float BLDCMotor::controllerPI(float tracking_error, PI_s& cont){
321314
if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
322315

323316
// u(s) = (P + I/s)e(s)
324-
// tustin discretisation of the PI controller ( a bit optimised )
317+
// Tustin transform of the PI controller ( a bit optimized )
325318
// uk = uk_1 + (I*Ts/2 + P)*ek + (I*Ts/2 - P)*ek_1
326319
float tmp = cont.I*Ts*0.5;
327320
float voltage = cont.voltage_prev + (tmp + cont.P) * tracking_error + (tmp - cont.P) * cont.tracking_error_prev;
@@ -355,8 +348,36 @@ float BLDCMotor::positionP(float ek) {
355348
/**
356349
* Debugger functions
357350
*/
358-
// funciton implementing the debugger setter
351+
// function implementing the debugger setter
359352
void BLDCMotor::useDebugging(Print &print){
360-
debugger = &print; //operate on the adress of print
353+
debugger = &print; //operate on the address of print
361354
if(debugger )debugger->println("DEBUG: Serial debugger enabled!");
355+
}
356+
// utility function intended to be used with serial plotter to monitor motor variables
357+
// significantly slowing the execution down!!!!
358+
void BLDCMotor::monitor() {
359+
if(!debugger) return;
360+
switch (controller) {
361+
case ControlType::velocity:
362+
debugger->print(voltage_q);
363+
debugger->print("\t");
364+
debugger->print(shaft_velocity_sp);
365+
debugger->print("\t");
366+
debugger->println(shaft_velocity);
367+
break;
368+
case ControlType::angle:
369+
debugger->print(voltage_q);
370+
debugger->print("\t");
371+
debugger->print(shaft_angle_sp);
372+
debugger->print("\t");
373+
debugger->println(shaft_angle);
374+
break;
375+
case ControlType::voltage:
376+
debugger->print(voltage_q);
377+
debugger->print("\t");
378+
debugger->print(shaft_angle);
379+
debugger->print("\t");
380+
debugger->println(shaft_velocity);
381+
break;
382+
}
362383
}

arduino_foc_minimal_encoder/BLDCMotor.h

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
#define BLDCMotor_h
33

44
#include "Arduino.h"
5+
#include "MagneticSensor.h"
6+
#include "Encoder.h"
57
#include "FOCutils.h"
68
#include "Sensor.h"
79

@@ -32,7 +34,7 @@ enum ControlType{
3234
angle
3335
};
3436

35-
// PI controller strucutre
37+
// PI controller structure
3638
struct PI_s{
3739
float P;
3840
float I;
@@ -68,7 +70,7 @@ class BLDCMotor
6870
- phA, phB, phC - motor A,B,C phase pwm pins
6971
- pp - pole pair number
7072
- cpr - counts per rotation number (cpm=ppm*4)
71-
- enable pin - (optionl input)
73+
- enable pin - (optional input)
7274
*/
7375
BLDCMotor(int phA,int phB,int phC,int pp, int en = 0);
7476
// change driver state
@@ -112,10 +114,10 @@ class BLDCMotor
112114
// current voltage u_q set
113115
float voltage_q;
114116

115-
// Power supply woltage
117+
// Power supply voltage
116118
float voltage_power_supply;
117119

118-
// configuraion structures
120+
// configuration structures
119121
ControlType controller;
120122
PI_s PI_velocity;
121123
PI_s PI_velocity_index_search;
@@ -137,22 +139,23 @@ class BLDCMotor
137139

138140
// debugging
139141
void useDebugging(Print &print);
142+
void monitor();
140143
Print* debugger;
141144

142145
float Ua,Ub,Uc;
143146

144147
private:
145148
//Sensor alignment to electrical 0 angle
146149
int alignSensor();
147-
//Motor and sensor alignement to the sensors absolute 0 angle
150+
//Motor and sensor alignment to the sensors absolute 0 angle
148151
int absoluteZeroAlign();
149152

150153
//Electrical angle calculation
151154
float electricAngle(float shaftAngle);
152155
//Set phase voltaget to pwm output
153156
void setPwm(int pinPwm, float U);
154157

155-
/** Utility funcitons */
158+
/** Utility functions */
156159
//normalizing radian angle to [0,2PI]
157160
float normalizeAngle(float angle);
158161
// determining if the enable pin has been provided

arduino_foc_minimal_encoder/Encoder.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){
2626
index_pin = _index; // its 0 if not used
2727
index_pulse_counter = 0;
2828

29-
// velocity calculation varibles
29+
// velocity calculation variables
3030
prev_Th = 0;
3131
pulse_per_second = 0;
3232
prev_pulse_counter = 0;
@@ -87,7 +87,7 @@ void Encoder::handleIndex() {
8787
if(hasIndex()){
8888
int I = digitalRead(index_pin);
8989
if(I && !I_active){
90-
// aling encoder on each index
90+
// align encoder on each index
9191
if(index_pulse_counter){
9292
long tmp = pulse_counter;
9393
// corrent the counter value
@@ -111,7 +111,7 @@ float Encoder::getAngle(){
111111
}
112112
/*
113113
Shaft velocity calculation
114-
funciton using mixed time and frequency measurement technique
114+
function using mixed time and frequency measurement technique
115115
*/
116116
float Encoder::getVelocity(){
117117
// timestamp
@@ -157,20 +157,20 @@ int Encoder::needsAbsoluteZeroSearch(){
157157
int Encoder::hasAbsoluteZero(){
158158
return hasIndex();
159159
}
160-
// intialise counter to zero
160+
// initialize counter to zero
161161
float Encoder::initRelativeZero(){
162162
long angle_offset = -pulse_counter;
163163
pulse_counter = 0;
164164
pulse_timestamp = _micros();
165165
return _2PI * (angle_offset) / ((float)cpr);
166166
}
167-
// intialise index to zero
167+
// initialize index to zero
168168
float Encoder::initAbsoluteZero(){
169169
pulse_counter -= index_pulse_counter;
170170
prev_pulse_counter = pulse_counter;
171171
return (index_pulse_counter) / ((float)cpr) * (_2PI);
172172
}
173-
// private funciton used to determine if encoder has index
173+
// private function used to determine if encoder has index
174174
int Encoder::hasIndex(){
175175
return index_pin != 0;
176176
}
@@ -194,7 +194,7 @@ void Encoder::init(){
194194
// counter setup
195195
pulse_counter = 0;
196196
pulse_timestamp = _micros();
197-
// velocity calculation varibles
197+
// velocity calculation variables
198198
prev_Th = 0;
199199
pulse_per_second = 0;
200200
prev_pulse_counter = 0;
@@ -206,7 +206,7 @@ void Encoder::init(){
206206

207207
}
208208

209-
// funciton enabling hardware interrupts of the for the callback provided
209+
// function enabling hardware interrupts of the for the callback provided
210210
// if callback is not provided then the interrupt is not enabled
211211
void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
212212
// attach interrupt if functions provided
@@ -223,7 +223,7 @@ void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
223223
break;
224224
}
225225

226-
// if index used intialise the index interrupt
226+
// if index used initialize the index interrupt
227227
if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE);
228228
}
229229

0 commit comments

Comments
 (0)