Skip to content

Commit a24cbe0

Browse files
committed
typos and SPI freq to 10Mhz
1 parent ebeea8d commit a24cbe0

File tree

2 files changed

+24
-24
lines changed

2 files changed

+24
-24
lines changed

arduino_foc_minimal/MagneticSensor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@ MagneticSensor::MagneticSensor(int cs, float _cpr, int _angle_register){
1717

1818

1919
void MagneticSensor::init(){
20-
// 1MHz clock (AMS should be able to accept up to 10MHz)
21-
settings = SPISettings(1000000, MSBFIRST, SPI_MODE1);
20+
// 10MHz clock (AMS should be able to accept up to 10MHz)
21+
settings = SPISettings(10000000, MSBFIRST, SPI_MODE1);
2222

2323
//setup pins
2424
pinMode(chip_select_pin, OUTPUT);

arduino_foc_minimal/arduino_foc_minimal.ino

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -9,17 +9,17 @@
99
// - enable pin - (optional input)
1010
BLDCMotor motor = BLDCMotor(9, 10, 11, 11);
1111

12-
// // MagneticSensor(int cs, float _cpr, int _angle_register)
13-
// // cs - SPI chip select pin
14-
// // _cpr - counts per revolution
15-
// // _angle_register - (optional) angle read register - default 0x3FFF
16-
// MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF);
12+
// MagneticSensor(int cs, float _cpr, int _angle_register)
13+
// cs - SPI chip select pin
14+
// _cpr - counts per revolution
15+
// _angle_register - (optional) angle read register - default 0x3FFF
16+
MagneticSensor AS5x4x = MagneticSensor(10, 16384, 0x3FFF);
1717

1818

19-
Encoder encoder = Encoder(2, 3, 8192);
20-
// interrupt ruotine intialisation
21-
void doA(){encoder.handleA();}
22-
void doB(){encoder.handleB();}
19+
// Encoder encoder = Encoder(2, 3, 8192);
20+
// // interrupt ruotine intialisation
21+
// void doA(){encoder.handleA();}
22+
// void doB(){encoder.handleB();}
2323

2424
// // encoder interrupt init
2525
// PciListenerImp listenerA(encoder.pinA, doA);
@@ -30,9 +30,9 @@ void setup() {
3030
Serial.begin(115200);
3131

3232
// initialise magnetic sensor hardware
33-
// AS5x4x.init();
34-
encoder.init();
35-
encoder.enableInterrupts(doA,doB);
33+
AS5x4x.init();
34+
// encoder.init();
35+
// encoder.enableInterrupts(doA,doB);
3636

3737
// // interrupt intitialisation
3838
// PciManager.registerListener(&listenerA);
@@ -69,8 +69,8 @@ void setup() {
6969

7070

7171
// link the motor to the sensor
72-
// motor.linkSensor(&AS5x4x);
73-
motor.linkSensor(&encoder);
72+
motor.linkSensor(&AS5x4x);
73+
// motor.linkSensor(&encoder);
7474

7575
// use debugging with serial for motor init
7676
// comment out if not needed
@@ -82,15 +82,15 @@ void setup() {
8282
motor.initFOC();
8383

8484
Serial.println("Motor ready.\n");
85-
Serial.println("Update all the PI contorller paramters from the serial temrinal:");
85+
Serial.println("Update all the PI controller parameters from the serial terminal:");
8686
Serial.println("- Type P100.2 to you the PI_velocity.P in 100.2");
8787
Serial.println("- Type I72.32 to you the PI_velocity.I in 72.32\n");
8888
Serial.println("Update the time constant of the velocity filter:");
8989
Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n");
90-
Serial.println("Check the loop executoion time (average):");
90+
Serial.println("Check the loop execution time (average):");
9191
Serial.println("- Type T\n");
9292
Serial.println("Change control loop type by typing:");
93-
Serial.println("- C0 - angle contro");
93+
Serial.println("- C0 - angle control");
9494
Serial.println("- C1 - velocity control");
9595
Serial.println("- C2 - voltage control\n");
9696
Serial.println("Initial parameters:");
@@ -106,7 +106,7 @@ void setup() {
106106
}
107107

108108
// target velocity variable
109-
float target_velocity = 0;
109+
float target = 0;
110110
// loop stats variables
111111
unsigned long t = 0;
112112
long timestamp = _micros();
@@ -117,7 +117,7 @@ void loop() {
117117

118118
// iterative function setting the outter loop target
119119
// velocity, position or voltage
120-
motor.move(target_velocity);
120+
motor.move(target);
121121

122122
// keep track of loop number
123123
t++;
@@ -209,9 +209,9 @@ void serialEvent() {
209209
t = 0;
210210
timestamp = _micros();
211211
}else{
212-
target_velocity = inputString.toFloat();
213-
Serial.print("Tagret Velocity: ");
214-
Serial.println(target_velocity);
212+
target = inputString.toFloat();
213+
Serial.print("Target : ");
214+
Serial.println(target);
215215
inputString = "";
216216
}
217217
inputString = "";

0 commit comments

Comments
 (0)