Skip to content

Commit b5bdbda

Browse files
committed
Fixed typos on examples
1 parent 64937c0 commit b5bdbda

File tree

2 files changed

+31
-26
lines changed

2 files changed

+31
-26
lines changed
Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,19 @@
1-
// Open loop motor control example
1+
// Open loop motor control example
22
#include <SimpleFOC.h>
33

44

55
// BLDC motor & driver instance
6+
// BLDCMotor motor = BLDCMotor(pole pair number);
67
BLDCMotor motor = BLDCMotor(11);
8+
// BLDCMotor motor = BLDCMotor(pole pair number);
79
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
10+
811
// Stepper motor & driver instance
912
//StepperMotor motor = StepperMotor(50);
1013
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
1114

1215
void setup() {
13-
16+
1417
// driver config
1518
// power supply voltage [V]
1619
driver.voltage_power_supply = 12;
@@ -19,24 +22,24 @@ void setup() {
1922
motor.linkDriver(&driver);
2023

2124
// limiting motor movements
22-
motor.voltage_limit = 3; // rad/s
23-
motor.velocity_limit = 20; // rad/s
25+
motor.voltage_limit = 3; // [V]
26+
motor.velocity_limit = 20; // [rad/s]
2427
// open loop control config
2528
motor.controller = ControlType::angle_openloop;
2629

2730
// init motor hardware
2831
motor.init();
29-
32+
3033

3134
Serial.begin(115200);
3235
Serial.println("Motor ready!");
3336
_delay(1000);
3437
}
3538

36-
float target_position = 0; // rad/s
39+
float target_position = 0; // [rad/s]
3740

3841
void loop() {
39-
// open loop angle movements
42+
// open loop angle movements
4043
// using motor.voltage_limit and motor.velocity_limit
4144
motor.move(target_position);
4245

@@ -47,25 +50,25 @@ void loop() {
4750
// utility function enabling serial communication with the user to set the target values
4851
// this function can be implemented in serialEvent function as well
4952
void serialReceiveUserCommand() {
50-
53+
5154
// a string to hold incoming data
5255
static String received_chars;
53-
56+
5457
while (Serial.available()) {
5558
// get the new byte:
5659
char inChar = (char)Serial.read();
5760
// add it to the string buffer:
5861
received_chars += inChar;
5962
// end of user input
6063
if (inChar == '\n') {
61-
64+
6265
// change the motor target
6366
target_position = received_chars.toFloat();
6467
Serial.print("Target position: ");
6568
Serial.println(target_position);
66-
67-
// reset the command buffer
69+
70+
// reset the command buffer
6871
received_chars = "";
6972
}
7073
}
71-
}
74+
}
Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,19 @@
1-
// Open loop motor control example
1+
// Open loop motor control example
22
#include <SimpleFOC.h>
33

44

55
// BLDC motor & driver instance
6+
// BLDCMotor motor = BLDCMotor(pole pair number);
67
BLDCMotor motor = BLDCMotor(11);
8+
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
79
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
10+
811
// Stepper motor & driver instance
912
//StepperMotor motor = StepperMotor(50);
1013
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
1114

1215
void setup() {
13-
16+
1417
// driver config
1518
// power supply voltage [V]
1619
driver.voltage_power_supply = 12;
@@ -19,25 +22,24 @@ void setup() {
1922
motor.linkDriver(&driver);
2023

2124
// limiting motor movements
22-
motor.voltage_limit = 3; // rad/s
23-
motor.velocity_limit = 20; // rad/s
25+
motor.voltage_limit = 3; // [V]
26+
motor.velocity_limit = 20; // [rad/s]
2427

2528
// open loop control config
2629
motor.controller = ControlType::velocity_openloop;
2730

2831
// init motor hardware
2932
motor.init();
30-
3133

3234
Serial.begin(115200);
3335
Serial.println("Motor ready!");
3436
_delay(1000);
3537
}
3638

37-
float target_velocity = 0; // rad/s
39+
float target_velocity = 0; // [rad/s]
3840

3941
void loop() {
40-
// open loop velocity movement
42+
// open loop velocity movement
4143
// using motor.voltage_limit and motor.velocity_limit
4244
motor.move(target_velocity);
4345

@@ -48,25 +50,25 @@ void loop() {
4850
// utility function enabling serial communication with the user to set the target values
4951
// this function can be implemented in serialEvent function as well
5052
void serialReceiveUserCommand() {
51-
53+
5254
// a string to hold incoming data
5355
static String received_chars;
54-
56+
5557
while (Serial.available()) {
5658
// get the new byte:
5759
char inChar = (char)Serial.read();
5860
// add it to the string buffer:
5961
received_chars += inChar;
6062
// end of user input
6163
if (inChar == '\n') {
62-
64+
6365
// change the motor target
6466
target_velocity = received_chars.toFloat();
6567
Serial.print("Target velocity ");
6668
Serial.println(target_velocity);
67-
68-
// reset the command buffer
69+
70+
// reset the command buffer
6971
received_chars = "";
7072
}
7173
}
72-
}
74+
}

0 commit comments

Comments
 (0)