added miniskid
This commit is contained in:
2
Miniskid/FW/lib/Cdrv8833/.gitattributes
vendored
Executable file
2
Miniskid/FW/lib/Cdrv8833/.gitattributes
vendored
Executable file
@@ -0,0 +1,2 @@
|
||||
# Auto detect text files and perform LF normalization
|
||||
* text=auto
|
||||
1
Miniskid/FW/lib/Cdrv8833/.piopm
Executable file
1
Miniskid/FW/lib/Cdrv8833/.piopm
Executable file
@@ -0,0 +1 @@
|
||||
{"type": "library", "name": "Cdrv8833", "version": "1.0.1", "spec": {"owner": "shurillu", "id": 14351, "name": "Cdrv8833", "requirements": null, "uri": null}}
|
||||
21
Miniskid/FW/lib/Cdrv8833/LICENSE
Executable file
21
Miniskid/FW/lib/Cdrv8833/LICENSE
Executable file
@@ -0,0 +1,21 @@
|
||||
MIT License
|
||||
|
||||
Copyright (c) 2022 Stefano Ledda
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
||||
109
Miniskid/FW/lib/Cdrv8833/README.md
Executable file
109
Miniskid/FW/lib/Cdrv8833/README.md
Executable file
@@ -0,0 +1,109 @@
|
||||
# Cdrv8833
|
||||
|
||||
<img src="https://github.com/shurillu/Cdrv8833/blob/f3dccc3f0448b2a2071de1e72d5ad1d12b7a835d/images/DRV8833.jpg" alt="DRV8833 module" width="180"/>
|
||||
|
||||
### Introduction
|
||||
Cdrv883 is a wrapper class for using modules based on DRV8833 H-bridge from Texas Instruments.
|
||||
|
||||
### News
|
||||
+ First public version released.
|
||||
|
||||
### Simple usage
|
||||
See the drv8833Tester example provided in the [examples folder](https://github.com/shurillu/Cdrv8833/tree/main/examples/drv8833Tester).
|
||||
|
||||
### Changelog
|
||||
+ 1.0.0 Initial version.
|
||||
|
||||
<hr>
|
||||
|
||||
### Reference
|
||||
|
||||
#### `Cdrv8833()`
|
||||
Default constructor. The object is NOT initialized: the `init` member function must be called. Decay mode is set to SLOW.
|
||||
<br><br>
|
||||
|
||||
#### `Cdrv8833(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection = false)`
|
||||
Specialized constructor. Decay mode is set to SLOW.
|
||||
|
||||
input:
|
||||
+ `in1Pin`: DRV8833 AIN1/BIN1
|
||||
+ `in2Pin`: DRV8833 AIN2/BIN2
|
||||
+ `channel`: ESP32 PWM channel (0..15) - ESP32 ledc functions
|
||||
+ `swapDirection`: swap motor rotation direction
|
||||
|
||||
There are 16 independent channels for PWM modulation inside the ESP32 SOC. Every motor need to have its own channel in order to work independently each other.
|
||||
|
||||
Swapping the motor rotation direction is useful (for example):
|
||||
+ wrong cabling
|
||||
+ using two motors to drive a two wheels vehicle (left wheel, right wheel).
|
||||
<br><br>
|
||||
|
||||
#### `bool init(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection = false)`
|
||||
Initialize the object. Decay mode is set to SLOW.
|
||||
|
||||
input:
|
||||
+ `in1Pin`: DRV8833 AIN1/BIN1
|
||||
+ `in2Pin`: DRV8833 AIN2/BIN2
|
||||
+ `channel`: ESP32 PWM channel (0..15) - ESP32 ledc functions
|
||||
+ `swapDirection`: swap motor rotation direction
|
||||
|
||||
Return `true` if no error occurs.
|
||||
|
||||
There are 16 independent channels for PWM modulation inside the ESP32 SOC. Every motor need to have its own channel in order to work independently each other.
|
||||
|
||||
Swapping the motor rotation direction is useful (for example):
|
||||
+ wrong cabling
|
||||
+ using two motors to drive a two wheels vehicle (left wheel, right wheel).
|
||||
<br><br>
|
||||
|
||||
#### `bool move(int8_t power)`
|
||||
Set motor rotation direction/speed.
|
||||
|
||||
input:
|
||||
+ `power`: rotation power. -100..100
|
||||
|
||||
Return `true` if no error occurs.
|
||||
|
||||
The `power` parameter set the rotation speed and the direction. Negative values means reverse rotation direction. Value span to -100 (full speed reverse direction) to 100 (full speed forward direction).
|
||||
|
||||
Zero stop the motor rotation.
|
||||
<br><br>
|
||||
|
||||
#### `bool stop()`
|
||||
Stop the motor, using fast decay mode.
|
||||
|
||||
Return `true` if no error occurs.
|
||||
<br><br>
|
||||
|
||||
#### `bool brake()`
|
||||
Stop the motor, using slow decay mode.
|
||||
|
||||
Return `true` if no error occurs.
|
||||
<br><br>
|
||||
|
||||
#### `void setDecayMode(drv8833DecayMode decayMode)`
|
||||
Set the decay mode. Default decay mode is set to SLOW.
|
||||
|
||||
input:
|
||||
+ `decayMode`: new decay mode. Values are
|
||||
+ `drv8833DecaySlow` good torque, but high power consumption
|
||||
+ `drv8833DecayFast` poor torque, but low power consumption
|
||||
<br><br>
|
||||
|
||||
#### `void setFrequency(uint32_t frequency)`
|
||||
Set the frequency used for the PWM modulation(for ESP32 ledc functions). Default value is 5000Hz. Allowed values are 1Hz..50000Hz.
|
||||
|
||||
input:
|
||||
+ `frequency`: new frequency in Hertz. 1..50000Hz
|
||||
<br><br>
|
||||
|
||||
#### `void swapDirection(bool swapDirection)`
|
||||
Swap the motor rotation direction.
|
||||
Useful for wrong cabling / driving two opposite motors (left wheel and right wheel of a vehicle)
|
||||
|
||||
input:
|
||||
+ `swapDirection`: swap/unswap the motor rotation direction
|
||||
+ `true`: swap rotation direction
|
||||
+ `false`: default rotation direction
|
||||
|
||||
|
||||
83
Miniskid/FW/lib/Cdrv8833/examples/drv8833Tester/drv8833Tester.ino
Executable file
83
Miniskid/FW/lib/Cdrv8833/examples/drv8833Tester/drv8833Tester.ino
Executable file
@@ -0,0 +1,83 @@
|
||||
/*
|
||||
Name: drv8833Tester.ino
|
||||
Created: 16/08/2022 10:06:02
|
||||
Author: Stefano Ledda
|
||||
Email: shurillu@tiscalinet.it
|
||||
GitHub: https://github.com/shurillu/Cdrv8833
|
||||
Note: Simple sketch to test the DRV8833 H-Bridge
|
||||
- connect the GPIO 12 to the xIN1 of the DRV8833 module
|
||||
- connect the GPIO 13 to the xIN2 of the DRV8833 module
|
||||
- connect the positive pole of the motor to the xOUT1 of the DRV8833 module
|
||||
- connect the negative pole of the motor to the xOUT2 of the DRV8833 module
|
||||
- power the DRV8833 module (if the motor is small, 5V and <500mA, you can power
|
||||
the module pulling the 5V and GND from the ESP32 board)
|
||||
- load the sketch
|
||||
- use the serial console to send commands
|
||||
*/
|
||||
|
||||
#include "Cdrv8833.h"
|
||||
|
||||
#define IN1_PIN 12 // in1 pin from one of the two DRV8833 H-bridge
|
||||
#define IN2_PIN 13 // in2 pin from one of the two DRV8833 H-bridge
|
||||
#define CHANNEL 0 // there are 16 unique PWM channels (0..15)
|
||||
#define SWAP false // swap motor rotation direction
|
||||
|
||||
Cdrv8833 myMotor; // default constructor
|
||||
|
||||
// you can initialize the object directly with the specialized constructor:
|
||||
// Cdrv8833 myMotor2(IN1_PIN, IN2_PIN, CHANNEL, SWAP);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println("\n");
|
||||
Serial.println("DRV8833 tester");
|
||||
Serial.println("--------------");
|
||||
Serial.printf("IN1 pin: %u\nIN2 pin: %u\n\n", IN1_PIN, IN2_PIN);
|
||||
|
||||
Serial.println("SWAP - swap motor rotation direction.");
|
||||
Serial.println("NOSWAP - restore motor rotation direction.");
|
||||
Serial.println("SLOW - decay mode SLOW - good torque, high power consumption.");
|
||||
Serial.println("FAST - decay mode FAST - poor torque, low power consumption.");
|
||||
Serial.println("MOVEXXX - start rotation (XXX = -100..100).");
|
||||
Serial.println("STOP - stop the motor.");
|
||||
|
||||
// initialize the object. Not needed if the initialization is done with the specialized constructor
|
||||
myMotor.init(IN1_PIN, IN2_PIN, CHANNEL, SWAP);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
String command;
|
||||
if (Serial.available()) { // check Serial for new command
|
||||
command = Serial.readString(); // read the new command from Serial
|
||||
command.toLowerCase(); // convert it to lowercase
|
||||
|
||||
if (command.equals("swap")) {
|
||||
myMotor.swapDirection(true); // swap rotation direction
|
||||
Serial.println("--> swapped rotation direction.");
|
||||
}
|
||||
else if (command.equals("noswap")) {
|
||||
myMotor.swapDirection(false); // default rotation direction
|
||||
Serial.println("--> default rotation direction.");
|
||||
}
|
||||
else if (command.equals("slow")) {
|
||||
myMotor.setDecayMode(drv8833DecaySlow); // decay mode SLOW
|
||||
Serial.println("--> Decay mode SLOW - good torque.");
|
||||
}
|
||||
else if (command.equals("fast")) {
|
||||
myMotor.setDecayMode(drv8833DecayFast); // decay mode FAST
|
||||
Serial.println("--> Decay mode FAST - poor torque.");
|
||||
}
|
||||
else if (command.equals("stop")) {
|
||||
myMotor.stop(); // stop moto rotation
|
||||
Serial.println("--> Motor stopped.");
|
||||
}
|
||||
else if (command.startsWith("move")) {
|
||||
command.replace("move", ""); // remove the word "move"
|
||||
command.replace(" ", ""); // remove spaces (if present)
|
||||
myMotor.move(command.toInt()); // start rotation at desired speed
|
||||
Serial.printf("--> Motor rotation speed: %ld.\n", command.toInt());
|
||||
}
|
||||
}
|
||||
}
|
||||
14
Miniskid/FW/lib/Cdrv8833/keywords.txt
Executable file
14
Miniskid/FW/lib/Cdrv8833/keywords.txt
Executable file
@@ -0,0 +1,14 @@
|
||||
Cdrv8833 KEYWORD1
|
||||
|
||||
init KEYWORD2
|
||||
move KEYWORD2
|
||||
stop KEYWORD2
|
||||
brake KEYWORD2
|
||||
setDecayMode KEYWORD2
|
||||
setFrequency KEYWORD2
|
||||
swapDirection KEYWORD2
|
||||
|
||||
drv8833DecayMode KEYWORD3
|
||||
|
||||
drv8833DecaySlow LITERAL1
|
||||
drv8833DecayFast LITERAL1
|
||||
19
Miniskid/FW/lib/Cdrv8833/library.json
Executable file
19
Miniskid/FW/lib/Cdrv8833/library.json
Executable file
@@ -0,0 +1,19 @@
|
||||
{
|
||||
"name": "Cdrv8833",
|
||||
"keywords": "DRV8833, motor driver, ESP32, h-bridge",
|
||||
"description": "ESP32 class for the TI DRV8833 motor driver. Designed for unipolar (DC) motors only (not stepper).",
|
||||
"homepage": "https://github.com/shurillu/Cdrv8833",
|
||||
"repository": {
|
||||
"type": "git",
|
||||
"url": "https://github.com/shurillu/Cdrv8833.git"
|
||||
},
|
||||
"version": "1.0.1",
|
||||
"authors": {
|
||||
"name": "Stefano Ledda",
|
||||
"email": "shurillu@tiscalinet.it"
|
||||
},
|
||||
"frameworks": "arduino",
|
||||
"platforms": "esp32",
|
||||
"dependencies": {
|
||||
}
|
||||
}
|
||||
9
Miniskid/FW/lib/Cdrv8833/library.properties
Executable file
9
Miniskid/FW/lib/Cdrv8833/library.properties
Executable file
@@ -0,0 +1,9 @@
|
||||
name=Cdrv8833
|
||||
version=1.0.1
|
||||
author=Stefano Ledda <shurillu@tiscalinet.it>
|
||||
maintainer=Stefano Ledda <shurillu@tiscalinet.it>
|
||||
sentence=ESP32 class for the TI DRV8833 motor driver. Designed for unipolar (DC) motors only (not stepper).
|
||||
paragraph=An easy to use class for driving DC motors with the Texas Instruments DRV8833 driver. Designed only for ESP32 platform.
|
||||
category=Communication
|
||||
url=https://github.com/shurillu/Cdrv8833
|
||||
architectures=esp32
|
||||
138
Miniskid/FW/lib/Cdrv8833/src/Cdrv8833.cpp
Executable file
138
Miniskid/FW/lib/Cdrv8833/src/Cdrv8833.cpp
Executable file
@@ -0,0 +1,138 @@
|
||||
#include "Cdrv8833.h"
|
||||
#include "esp32-hal-gpio.h"
|
||||
|
||||
Cdrv8833::Cdrv8833() {
|
||||
// not initialized
|
||||
m_in1Pin = -1;
|
||||
m_in2Pin = -1;
|
||||
m_power = 0;
|
||||
m_swapDirection = false;
|
||||
m_decayMode = drv8833DecaySlow;
|
||||
}
|
||||
|
||||
Cdrv8833::Cdrv8833(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection) {
|
||||
init(in1Pin, in2Pin, channel, swapDirection);
|
||||
}
|
||||
|
||||
Cdrv8833::~Cdrv8833() {
|
||||
stop();
|
||||
}
|
||||
|
||||
bool Cdrv8833::init(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection) {
|
||||
if (channel > 15)
|
||||
return false;
|
||||
if ((m_in1Pin != -1) && (m_in2Pin != -1))
|
||||
stop();
|
||||
pinMode(in1Pin, OUTPUT);
|
||||
pinMode(in2Pin, OUTPUT);
|
||||
m_in1Pin = in1Pin;
|
||||
m_in2Pin = in2Pin;
|
||||
m_power = 0;
|
||||
m_swapDirection = swapDirection;
|
||||
m_channel = channel;
|
||||
m_decayMode = drv8833DecaySlow;
|
||||
ledcSetup(channel, PWM_FREQUENCY, PWM_BIT_RESOLUTION);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Cdrv8833::move(int8_t power) {
|
||||
if (-1 == m_in1Pin)
|
||||
return false;
|
||||
if (-1 == m_in2Pin)
|
||||
return false;
|
||||
if (0 == power) {
|
||||
stop();
|
||||
return true;
|
||||
}
|
||||
if (power > 100)
|
||||
power = 100;
|
||||
if (power < -100)
|
||||
power = -100;
|
||||
m_power = power;
|
||||
|
||||
if (m_swapDirection)
|
||||
power = -power;
|
||||
float value = (float)((1 << PWM_BIT_RESOLUTION) - 1) * ((float)abs(power))/100.0;
|
||||
uint32_t dutyCycle;
|
||||
|
||||
if ((value - trunc(value)) < 0.5)
|
||||
dutyCycle = value;
|
||||
else
|
||||
dutyCycle = value + 1;
|
||||
|
||||
if (drv8833DecaySlow == m_decayMode)
|
||||
dutyCycle = ((1 << PWM_BIT_RESOLUTION) - 1) - dutyCycle;
|
||||
|
||||
if (power > 0) { // forward
|
||||
if (drv8833DecayFast == m_decayMode) {
|
||||
// forward fast decay
|
||||
ledcDetachPin(m_in2Pin);
|
||||
digitalWrite(m_in2Pin, LOW);
|
||||
ledcAttachPin(m_in1Pin, m_channel);
|
||||
}
|
||||
else {
|
||||
// forward slow decay
|
||||
ledcDetachPin(m_in1Pin);
|
||||
digitalWrite(m_in1Pin, HIGH);
|
||||
ledcAttachPin(m_in2Pin, m_channel);
|
||||
}
|
||||
}
|
||||
else { // reverse
|
||||
if (drv8833DecayFast == m_decayMode) {
|
||||
// reverse fast decay
|
||||
ledcDetachPin(m_in1Pin);
|
||||
digitalWrite(m_in1Pin, LOW);
|
||||
ledcAttachPin(m_in2Pin, m_channel);
|
||||
}
|
||||
else {
|
||||
// reverse slow decay
|
||||
ledcDetachPin(m_in2Pin);
|
||||
digitalWrite(m_in2Pin, HIGH);
|
||||
ledcAttachPin(m_in1Pin, m_channel);
|
||||
}
|
||||
}
|
||||
ledcWrite(m_channel, dutyCycle);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Cdrv8833::stop() {
|
||||
if (-1 == m_in1Pin)
|
||||
return false;
|
||||
if (-1 == m_in2Pin)
|
||||
return false;
|
||||
ledcDetachPin(m_in1Pin);
|
||||
ledcDetachPin(m_in2Pin);
|
||||
digitalWrite(m_in1Pin, LOW);
|
||||
digitalWrite(m_in2Pin, LOW);
|
||||
m_power = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Cdrv8833::brake() {
|
||||
if (-1 == m_in1Pin)
|
||||
return false;
|
||||
if (-1 == m_in2Pin)
|
||||
return false;
|
||||
ledcDetachPin(m_in1Pin);
|
||||
ledcDetachPin(m_in2Pin);
|
||||
digitalWrite(m_in1Pin, HIGH);
|
||||
digitalWrite(m_in2Pin, HIGH);
|
||||
m_power = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
void Cdrv8833::setDecayMode(drv8833DecayMode decayMode) {
|
||||
stop();
|
||||
m_decayMode = decayMode;
|
||||
}
|
||||
|
||||
void Cdrv8833::setFrequency(uint32_t frequency) {
|
||||
stop();
|
||||
ledcChangeFrequency(m_channel, frequency, PWM_BIT_RESOLUTION);
|
||||
}
|
||||
|
||||
void Cdrv8833::swapDirection(bool swapDirection) {
|
||||
stop();
|
||||
m_swapDirection = swapDirection;
|
||||
}
|
||||
|
||||
91
Miniskid/FW/lib/Cdrv8833/src/Cdrv8833.h
Executable file
91
Miniskid/FW/lib/Cdrv8833/src/Cdrv8833.h
Executable file
@@ -0,0 +1,91 @@
|
||||
#ifndef DRV8833_H
|
||||
#define DRV8833_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// default values
|
||||
#define PWM_FREQUENCY 5000 // 1 - 50000 Hz
|
||||
#define PWM_BIT_RESOLUTION 8 // pwm bit resolution
|
||||
|
||||
// https://learn.adafruit.com/improve-brushed-dc-motor-performance/choosing-decay-mode-and-pwm-frequency
|
||||
// DRV8833 PWM: min - 1Hz, max - 50KHz (provare 100-500Hz)
|
||||
// PWM utilizzare le funzioni ledc
|
||||
|
||||
// slow decay -> good torque, high power consumption
|
||||
// fast decay -> poor torque, low power consumption
|
||||
enum drv8833DecayMode {
|
||||
drv8833DecaySlow = 0,
|
||||
drv8833DecayFast = 1
|
||||
};
|
||||
|
||||
class Cdrv8833 {
|
||||
public:
|
||||
// default constructor. Default decay mode: SLOW
|
||||
Cdrv8833();
|
||||
|
||||
// Specialized constructor. Default decay mode: SLOW
|
||||
// input:
|
||||
// in1Pin : DRV8833 AIN1/BIN1
|
||||
// in2Pin : DRV8833 AIN2/BIN2
|
||||
// channel : ESP32 PWM channel (0..15) - ESP32 ledc functions
|
||||
// swapDirection: swap motor rotation direction
|
||||
Cdrv8833(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection = false);
|
||||
~Cdrv8833();
|
||||
|
||||
// Initialize the DRV8833 object. Default decay mode: SLOW
|
||||
// input:
|
||||
// in1Pin : DRV8833 AIN1/BIN1
|
||||
// in2Pin : DRV8833 AIN2/BIN2
|
||||
// channel : ESP32 PWM channel (0..15) - ESP32 ledc functions
|
||||
// swapDirection: swap motor rotation direction
|
||||
// return:
|
||||
// true if no error occurs.
|
||||
bool init(uint8_t in1Pin, uint8_t in2Pin, uint8_t channel, bool swapDirection = false);
|
||||
|
||||
// Set motor rotation direction/speed
|
||||
// input:
|
||||
// power: rotation power. -100..100
|
||||
// Negative numbers mean reverse rotation; positive numbers mean forward direction.
|
||||
// Zero stop the rotation
|
||||
// return:
|
||||
// true if no error occurs.
|
||||
bool move(int8_t power); // use fast decay -> smooth movement
|
||||
|
||||
// Stop the motor, using fast decay mode
|
||||
// return:
|
||||
// true if no error occurs.
|
||||
bool stop();
|
||||
|
||||
// Stop the motor, using slow decay mode
|
||||
// return:
|
||||
// true if no error occurs.
|
||||
bool brake();
|
||||
|
||||
// Set the decay mode. Default decay mode: SLOW
|
||||
// input:
|
||||
// decayMode: new decay mode. Values are
|
||||
// drv8833DecaySlow - good torque, high power consumption
|
||||
// drv8833DecayFast - poor torque, low power consumption
|
||||
void setDecayMode(drv8833DecayMode decayMode);
|
||||
|
||||
// Set the PWM frequency (for ESP32 ledc functions)
|
||||
// input:
|
||||
// frequency: new frequency in Hertz. 1..50000Hz.
|
||||
void setFrequency(uint32_t frequency);
|
||||
|
||||
// Swap the motor rotation direction.
|
||||
// Useful for wrong cabling / driving two opposite motors (left wheel + right wheel motor of a vehicle)
|
||||
// input:
|
||||
// swapDirection: true -> swap rotation direction
|
||||
void swapDirection(bool swapDirection);
|
||||
|
||||
private:
|
||||
int8_t m_in1Pin;
|
||||
int8_t m_in2Pin;
|
||||
bool m_swapDirection;
|
||||
drv8833DecayMode m_decayMode;
|
||||
uint8_t m_channel;
|
||||
int8_t m_power;
|
||||
};
|
||||
|
||||
#endif
|
||||
46
Miniskid/FW/lib/README
Executable file
46
Miniskid/FW/lib/README
Executable file
@@ -0,0 +1,46 @@
|
||||
|
||||
This directory is intended for project specific (private) libraries.
|
||||
PlatformIO will compile them to static libraries and link into executable file.
|
||||
|
||||
The source code of each library should be placed in a an own separate directory
|
||||
("lib/your_library_name/[here are source files]").
|
||||
|
||||
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||
|
||||
|--lib
|
||||
| |
|
||||
| |--Bar
|
||||
| | |--docs
|
||||
| | |--examples
|
||||
| | |--src
|
||||
| | |- Bar.c
|
||||
| | |- Bar.h
|
||||
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||
| |
|
||||
| |--Foo
|
||||
| | |- Foo.c
|
||||
| | |- Foo.h
|
||||
| |
|
||||
| |- README --> THIS FILE
|
||||
|
|
||||
|- platformio.ini
|
||||
|--src
|
||||
|- main.c
|
||||
|
||||
and a contents of `src/main.c`:
|
||||
```
|
||||
#include <Foo.h>
|
||||
#include <Bar.h>
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
PlatformIO Library Dependency Finder will find automatically dependent
|
||||
libraries scanning project source files.
|
||||
|
||||
More information about PlatformIO Library Dependency Finder
|
||||
- https://docs.platformio.org/page/librarymanager/ldf.html
|
||||
Reference in New Issue
Block a user