Skip to content

Commit e9bfbba

Browse files
authored
Merge branch 'dev' into open_loop_velocity
2 parents 50a758b + 15cc0b3 commit e9bfbba

File tree

26 files changed

+814
-68
lines changed

26 files changed

+814
-68
lines changed

.github/workflows/ccpp.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,4 +11,4 @@ jobs:
1111
uses: ArminJo/[email protected]
1212
with:
1313
libraries: PciManager
14-
examples-exclude: bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example
14+
examples-exclude: bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, simplefoc_osc_esp32_3pwm

README.md

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,17 @@ Therefore this is an attempt to:
1111
- Develop a modular BLDC driver board: [Arduino *SimpleFOCShield*](https://docs.simplefoc.com/arduino_simplefoc_shield_showcase).
1212
- ***New 📢:** Develop a modular Stepper motor board for FOC control:* <b>Arduino <span class="simple">Stepper<span class="foc">FOC</span>Shield</span></b>
1313

14-
<blockquote class="info"><p> <b>NEW RELEASE 📢:</b> <i>Simple<b>FOC</b>library v2.0</i><br></p><ul><li><strong>6PWM support </strong> <b><a href="https://docs.simplefoc.com/drivers_config">See in docs!</a></b><ul><li>Arduino UNO (atmega328)</li><li>stm32 boards</li><li>esp32 boards</li></ul></li><li>BLDC driver code separated <b><a href="https://docs.simplefoc.com/code">See in docs!</a></b><ul><li> BLDC: 6pwm and 3pwm</li><li> Stepper: 4pwm</li><li> Hardware specific code in separate files</li><li> PWM config</li></ul></li><li>I2C and SPI sensors multiple busses support by <a href="https://github.com/owennewo">@owennewo</a> <b><a href="https://docs.simplefoc.com/magnetic_sensor">See in docs!</a></b></li><li>Hall sensor refactoring <a href="https://github.com/owennewo">@owennewo</a></li><li>A lot of refactoring</li></ul>Experimental features<ul><li>Initial implementation of Block commutation by <a href="https://github.com/owennewo">@owennewo</a><ul><li> FOCModulationType::Trapezoid_120</li><li> FOCModulationType::Trapezoid_150</li></ul></li><li>Added support for separate setting of <i>U<sub>d</sub></i> and <i>U<sub>q</sub></i> setting.<ul><li> Preparations for current control</li><li> Working only for SinePWM modulation at the moment</li></ul></li></ul></blockquote>
14+
15+
> <b>NEW RELEASE 📢:</b> <i>Simple<b>FOC</b>library v2.0.2
16+
> - Arduino MEGA 2560 support
17+
> - OSC example project
18+
19+
> <i>Simple<b>FOC</b>library v2.0.1
20+
> - ESP32 bugfix
21+
> - frequency setting
22+
> - pwm resolution
23+
> - 2PWM stepper class added `StepperMotor2PWM`
24+
> - some refactoring of examples
1525
1626
## Arduino *SimpleFOCShield*
1727

examples/.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
/.DS_Store
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+
}
511 Bytes
Binary file not shown.
Lines changed: 182 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,182 @@
1+
/**
2+
* Arduino SimpleFOC + OSC control example
3+
*
4+
* Simple example to show how you can control SimpleFOC via OSC.
5+
*
6+
* It's a nice way to work, easier than changing speeds via Seerial text input. It could also be the basis for
7+
* a functional UI, for example in a lab, art-gallery or similar situation.
8+
*
9+
* For this example we used an ESP32 to run the code, a AS5048B I2C absolute encoder
10+
* and a generic L298 driver board to drive a Emax 4114 gimbal motor. But there is no reason the OSC part will
11+
* not work with any other setup.
12+
*
13+
* You will need:
14+
*
15+
* - a working SimpleFOC setup - motor, driver, encoder
16+
* - a MCU with WiFi and UDP support, for example an ESP32, or an Arduino with Ethernet Shield
17+
* - a device to run an OSC UI
18+
* - a configured OSC UI
19+
* - a WiFi network
20+
*
21+
* To do the OSC UI I used TouchOSC from https://hexler.net/products/touchosc
22+
* There is an example UI file that works with this sketch, see "layout1.touchosc"
23+
* You can open the UI file in 'TouchOSC Editor' (free program) and transfer it to the TouchOSC app on your device.
24+
*
25+
* Alternatively, there are other OSC UIs which may work, e.g. http://opensoundcontrol.org/implementations
26+
*
27+
* Using:
28+
*
29+
* Change the values below to match the WiFi ssid/password of your network.
30+
* Load and run the code on your ESP32. Take a note of the IP address of your ESP32.
31+
* Load and run the UI in TouchOSC.
32+
* Configure TouchOSC to connect to your ESP32.
33+
* The first command you send will cause the ESP32 to start sending responses to your TouchOSC device.
34+
* After this you will see motor position and speed in the UI.
35+
* Have fun controlling your SimpleFOC motors from your smartphone!
36+
*
37+
*/
38+
39+
40+
#include "Arduino.h"
41+
#include <SimpleFOC.h>
42+
43+
#include <WiFi.h>
44+
#include <WiFiUdp.h>
45+
46+
#include <OSCMessage.h>
47+
#include <OSCBundle.h>
48+
#include <OSCBoards.h>
49+
#include <Math.h>
50+
51+
52+
const char ssid[] = "myssid"; // your network SSID (name)
53+
const char pass[] = "mypassword"; // your network password
54+
WiFiUDP Udp;
55+
IPAddress outIp(192,168,1,17); // remote IP (not needed for receive)
56+
const unsigned int outPort = 8000; // remote port (not needed for receive)
57+
const unsigned int inPort = 8000; // local port to listen for UDP packets (here's where we send the packets)
58+
59+
60+
OSCErrorCode error;
61+
62+
MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);
63+
BLDCMotor motor = BLDCMotor(11);
64+
BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27);
65+
66+
67+
void setup() {
68+
Serial.begin(115200);
69+
70+
WiFi.begin(ssid, pass);
71+
72+
Serial.print("Connecting WiFi ");
73+
Serial.println(ssid);
74+
while (WiFi.status() != WL_CONNECTED) {
75+
delay(500);
76+
Serial.print(".");
77+
}
78+
Udp.begin(inPort);
79+
Serial.println();
80+
Serial.print("WiFi connected. Local OSC address: ");
81+
Serial.print(WiFi.localIP());
82+
Serial.print(":");
83+
Serial.println(inPort);
84+
85+
delay(2000);
86+
Serial.println("Initializing motor.");
87+
88+
sensor.init();
89+
motor.linkSensor(&sensor);
90+
driver.voltage_power_supply = 9;
91+
driver.init();
92+
motor.linkDriver(&driver);
93+
motor.controller = ControlType::velocity;
94+
motor.PID_velocity.P = 0.2;
95+
motor.PID_velocity.I = 20;
96+
motor.PID_velocity.D = 0.001;
97+
motor.PID_velocity.output_ramp = 1000;
98+
motor.LPF_velocity.Tf = 0.01;
99+
motor.voltage_limit = 8;
100+
//motor.P_angle.P = 20;
101+
motor.init();
102+
motor.initFOC();
103+
104+
Serial.println("All initialization complete.");
105+
}
106+
107+
// velocity set point variable
108+
float target_velocity = 2.0;
109+
// angle set point variable
110+
float target_angle = 1.0;
111+
112+
113+
void motorControl(OSCMessage &msg){
114+
if (msg.isInt(0))
115+
target_velocity = radians(msg.getInt(0));
116+
else if (msg.isFloat(0))
117+
target_velocity = radians(msg.getFloat(0));
118+
else if (msg.isDouble(0))
119+
target_velocity = radians(msg.getDouble(0));
120+
Serial.print("Velocity set to ");
121+
Serial.println(target_velocity);
122+
}
123+
124+
void cmdControl(OSCMessage &msg){
125+
char cmdStr[16];
126+
if (msg.isString(0)) {
127+
msg.getString(0,cmdStr,16);
128+
String it(cmdStr);
129+
motor.command(it);
130+
}
131+
}
132+
133+
long lastSend = 0;
134+
OSCMessage bundleIN;
135+
136+
void loop() {
137+
OSCBundle bundleOUT;
138+
139+
// FOC algorithm function
140+
motor.move(target_velocity);
141+
motor.loopFOC();
142+
143+
144+
int size = Udp.parsePacket();
145+
if (size > 0) {
146+
while (size--) {
147+
bundleIN.fill(Udp.read());
148+
}
149+
if (!bundleIN.hasError()) {
150+
bundleIN.dispatch("/mot1/S", motorControl);
151+
bundleIN.dispatch("/mot1/C", cmdControl);
152+
IPAddress ip = Udp.remoteIP();
153+
if (!( ip==outIp )) {
154+
Serial.print("New connection from ");
155+
Serial.println(ip);
156+
outIp = ip;
157+
}
158+
}
159+
else {
160+
error = bundleIN.getError();
161+
Serial.print("error: ");
162+
Serial.println(error);
163+
}
164+
bundleIN.empty();
165+
}
166+
else { // don't receive and send in the same loop...
167+
long now = millis();
168+
if (now - lastSend > 100) {
169+
int ang = (int)degrees(motor.shaftAngle()) % 360;
170+
if (ang<0) ang = 360-abs(ang);
171+
//BOSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
172+
bundleOUT.add("/mot1/A").add((int)ang);
173+
bundleOUT.add("/mot1/V").add((int)degrees(motor.shaftVelocity()));
174+
Udp.beginPacket(outIp, outPort);
175+
bundleOUT.send(Udp);
176+
Udp.endPacket();
177+
bundleOUT.empty(); // empty the bundle to free room for a new one
178+
lastSend = now;
179+
}
180+
}
181+
182+
}

0 commit comments

Comments
 (0)