Skip to content

Commit 5069e26

Browse files
author
Richard Unger
committed
Add SimpleFOCNano driver
1 parent 7d25dfc commit 5069e26

File tree

3 files changed

+189
-0
lines changed

3 files changed

+189
-0
lines changed
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
2+
# SimpleFOCNano Driver Class
3+
4+
The `SimpleFOCNanoDriver` is a wrapper class around BLDCDriver3PWM to make using the [SimpleFOCNano shield](link) super-simple.
5+
6+
If you use this driver you don't need to bother with any pin-numbers, they are all set correctly for you based on the SimpleFOCNano's pinout. Of course, this only works if you actually plug the shield into the Nano. If you use jumper wires, either make exactly the same connections as plugging in the shield would, or don't use this driver.
7+
8+
## Usage
9+
10+
Basic usage is very simple:
11+
12+
```c++
13+
#include <SimpleFOC.h>
14+
#include <SimpleFOCDrivers.h>
15+
#include <drivers/simplefocnano/SimpleFOCNanoDriver.h>
16+
17+
SimpleFOCNanoDriver driver = SimpleFOCNanoDriver();
18+
BLDCMotor motor = BLDCMotor(7);
19+
20+
void setup() {
21+
driver.voltage_power_supply = driver.getBusVoltage();
22+
driver.init();
23+
motor.linkDriver(driver);
24+
motor.voltage_limit = driver.voltage_limit / 2.0f;
25+
motor.controller = MotionControlMode::velocity_openloop;
26+
motor.init();
27+
}
28+
29+
void loop(){
30+
motor.move(2.0f); // 2 rads per second, open-loop
31+
}
32+
```
33+
34+
There are some extra features, you can check for faults, and clear the fault state:
35+
36+
```c++
37+
if (driver.isFault()) {
38+
motor.disable();
39+
driver.clearFault();
40+
}
41+
```
42+
43+
Or you can activate sleep mode to save power:
44+
45+
```c++
46+
driver.sleep();
47+
48+
// sometime later
49+
if (driver.isSleeping())
50+
driver.wake();
51+
```
52+
53+
As shown in the example you can read the bus voltage:
54+
55+
:warning: *this is a slow function. Do not call it while motor is running!*
56+
57+
```c++
58+
float val = driver.getBusVoltage(); // get the bus voltage, in Volts
59+
```
60+
61+
The driver's nCS pin is 10, and the constant PIN_nCS can be used:
62+
63+
```c++
64+
MagneticSensorAS5048A sensor = MagneticSensorAS5048A(PIN_nCS);
65+
```
Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
2+
#include "./SimpleFOCNanoDriver.h"
3+
4+
SimpleFOCNanoDriver::SimpleFOCNanoDriver() : BLDCDriver3PWM(PIN_INU, PIN_INV, PIN_INW, PIN_ENU, PIN_ENV, PIN_ENW) {
5+
// nothing to do here
6+
};
7+
8+
9+
SimpleFOCNanoDriver::~SimpleFOCNanoDriver() {
10+
// nothing to do here
11+
};
12+
13+
int SimpleFOCNanoDriver::init() {
14+
pinMode(PIN_nSLEEP, OUTPUT);
15+
pinMode(PIN_nRST, OUTPUT);
16+
pinMode(PIN_nFAULT, INPUT_PULLUP);
17+
pinMode(PIN_VBUS, INPUT);
18+
this->sleep(false);
19+
digitalWrite(PIN_nRST, HIGH);
20+
return BLDCDriver3PWM::init();
21+
};
22+
23+
void SimpleFOCNanoDriver::sleep(bool sleep) {
24+
digitalWrite(PIN_nSLEEP, !sleep);
25+
};
26+
27+
28+
void SimpleFOCNanoDriver::wake() {
29+
this->sleep(false);
30+
};
31+
32+
33+
bool SimpleFOCNanoDriver::isSleeping() {
34+
return digitalRead(PIN_nSLEEP)==LOW;
35+
};
36+
37+
38+
39+
bool SimpleFOCNanoDriver::isFault() {
40+
return !digitalRead(PIN_nFAULT);
41+
};
42+
43+
44+
void SimpleFOCNanoDriver::clearFault() {
45+
if (!this->isFault()) return;
46+
disable();
47+
digitalWrite(PIN_nRST, LOW);
48+
delayMicroseconds(100);
49+
digitalWrite(PIN_nRST, HIGH);
50+
enable();
51+
};
52+
53+
54+
void SimpleFOCNanoDriver::attachFaultInterrupt(void (*callback)()) {
55+
attachInterrupt(digitalPinToInterrupt(PIN_nFAULT), callback, FALLING);
56+
};
57+
58+
59+
60+
float SimpleFOCNanoDriver::getBusVoltage(float vdd_voltage, int adc_resolution) {
61+
float sum = 0.0;
62+
for(int i = 0; i < 500; i++) {
63+
sum += analogRead(PIN_VBUS);
64+
}
65+
66+
return sum / 500.0 * VBUS_CONV_FACTOR * (vdd_voltage / adc_resolution);
67+
};
68+
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
2+
#pragma once
3+
4+
#include <drivers/BLDCDriver3PWM.h>
5+
6+
/*
7+
* Default pins for the SimpleFOC Nano board
8+
*
9+
* These are the correct pins if you plug the Nano board into the SimpleFOC shield.
10+
* If you use jumper wires to connect, you can make your own pin choices. In this case, don't use this driver,
11+
* and rather use the BLDCDriver3PWM class directly.
12+
*
13+
*/
14+
15+
16+
#define PIN_INU 3
17+
#define PIN_INV 6
18+
#define PIN_INW 9
19+
#define PIN_ENU 4
20+
#define PIN_ENV 7
21+
#define PIN_ENW 8
22+
#ifdef ARDUINO_NANO_RP2040_CONNECT
23+
#define PIN_nSLEEP 17
24+
#define PIN_nFAULT 20
25+
#define PIN_nRST 21
26+
#else
27+
#define PIN_nSLEEP A3
28+
#define PIN_nFAULT A6
29+
#define PIN_nRST A7
30+
#endif
31+
#define PIN_VBUS A0
32+
#define PIN_nCS 10
33+
34+
#define VBUS_CONV_FACTOR (22.0f/2.2f)
35+
36+
37+
38+
39+
class SimpleFOCNanoDriver : public BLDCDriver3PWM {
40+
public:
41+
SimpleFOCNanoDriver();
42+
~SimpleFOCNanoDriver();
43+
44+
int init() override;
45+
46+
void sleep(bool sleep=true);
47+
void wake();
48+
bool isSleeping();
49+
50+
bool isFault();
51+
void clearFault();
52+
void attachFaultInterrupt(void (*callback)());
53+
54+
float getBusVoltage(float vdd_voltage, int adc_resolution);
55+
};
56+

0 commit comments

Comments
 (0)