Compare commits
7 Commits
ef9271b3cb
...
main
| Author | SHA1 | Date | |
|---|---|---|---|
| e818f45475 | |||
| 0c4edefa07 | |||
| cb6e65a8b4 | |||
| 6be67b5165 | |||
| fb89d957bd | |||
| e167ef6f5b | |||
| a0f5fc0a07 |
7
.gitignore
vendored
Executable file
7
.gitignore
vendored
Executable file
@@ -0,0 +1,7 @@
|
|||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
||||||
|
**.DS_Store
|
||||||
|
.vscode/extensions.json
|
||||||
BIN
Miniskid/CAD/Wiring Diagram.JPG
Executable file
BIN
Miniskid/CAD/Wiring Diagram.JPG
Executable file
Binary file not shown.
|
After Width: | Height: | Size: 98 KiB |
BIN
Miniskid/CAD/v20-3d-printed-rc-skidsteer-model_files.zip
Executable file
BIN
Miniskid/CAD/v20-3d-printed-rc-skidsteer-model_files.zip
Executable file
Binary file not shown.
5
Miniskid/FW/.gitignore
vendored
Executable file
5
Miniskid/FW/.gitignore
vendored
Executable file
@@ -0,0 +1,5 @@
|
|||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
||||||
39
Miniskid/FW/include/README
Executable file
39
Miniskid/FW/include/README
Executable file
@@ -0,0 +1,39 @@
|
|||||||
|
|
||||||
|
This directory is intended for project header files.
|
||||||
|
|
||||||
|
A header file is a file containing C declarations and macro definitions
|
||||||
|
to be shared between several project source files. You request the use of a
|
||||||
|
header file in your project source file (C, C++, etc) located in `src` folder
|
||||||
|
by including it, with the C preprocessing directive `#include'.
|
||||||
|
|
||||||
|
```src/main.c
|
||||||
|
|
||||||
|
#include "header.h"
|
||||||
|
|
||||||
|
int main (void)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Including a header file produces the same results as copying the header file
|
||||||
|
into each source file that needs it. Such copying would be time-consuming
|
||||||
|
and error-prone. With a header file, the related declarations appear
|
||||||
|
in only one place. If they need to be changed, they can be changed in one
|
||||||
|
place, and programs that include the header file will automatically use the
|
||||||
|
new version when next recompiled. The header file eliminates the labor of
|
||||||
|
finding and changing all the copies as well as the risk that a failure to
|
||||||
|
find one copy will result in inconsistencies within a program.
|
||||||
|
|
||||||
|
In C, the usual convention is to give header files names that end with `.h'.
|
||||||
|
It is most portable to use only letters, digits, dashes, and underscores in
|
||||||
|
header file names, and at most one dot.
|
||||||
|
|
||||||
|
Read more about using header files in official GCC documentation:
|
||||||
|
|
||||||
|
* Include Syntax
|
||||||
|
* Include Operation
|
||||||
|
* Once-Only Headers
|
||||||
|
* Computed Includes
|
||||||
|
|
||||||
|
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
||||||
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
|
||||||
28
Miniskid/FW/platformio.ini
Executable file
28
Miniskid/FW/platformio.ini
Executable file
@@ -0,0 +1,28 @@
|
|||||||
|
; PlatformIO Project Configuration File
|
||||||
|
;
|
||||||
|
; Build options: build flags, source filter
|
||||||
|
; Upload options: custom upload port, speed and extra flags
|
||||||
|
; Library options: dependencies, extra library storages
|
||||||
|
; Advanced options: extra scripting
|
||||||
|
;
|
||||||
|
; Please visit documentation for the other options and examples
|
||||||
|
; https://docs.platformio.org/page/projectconf.html
|
||||||
|
|
||||||
|
[env:esp32dev]
|
||||||
|
platform = espressif32
|
||||||
|
board = esp32dev
|
||||||
|
framework = arduino
|
||||||
|
monitor_speed = 115200
|
||||||
|
lib_deps =
|
||||||
|
madhephaestus/ESP32Servo@^1.1.0
|
||||||
|
; ottowinter/ESPAsyncWebServer-esphome@^3.1.0
|
||||||
|
; ArduinoWebsockets
|
||||||
|
; AsyncTCP
|
||||||
|
shurillu/Cdrv8833@^1.0.1
|
||||||
|
asukiaaa/XboxSeriesXControllerESP32_asukiaaa @ ^1.0.9
|
||||||
|
build_flags =
|
||||||
|
-DCORE_DEBUG_LEVEL=3
|
||||||
|
-DNDEF_DEBUG=1
|
||||||
|
upload_protocol = esptool
|
||||||
|
;upload_protocol = espota
|
||||||
|
;upload_port = miniskidi.local
|
||||||
110
Miniskid/FW/src/Motors.cpp
Executable file
110
Miniskid/FW/src/Motors.cpp
Executable file
@@ -0,0 +1,110 @@
|
|||||||
|
#include "motors.h"
|
||||||
|
|
||||||
|
bool removeArmMomentum = false;
|
||||||
|
|
||||||
|
Servo bucketServo;
|
||||||
|
Servo auxServo;
|
||||||
|
|
||||||
|
std::vector<MOTOR_PINS> motorPins =
|
||||||
|
{
|
||||||
|
{RMOTOR_IN1, RMOTOR_IN2}, // RIGHT_MOTOR Pins (IN1, IN2)
|
||||||
|
{LMOTOR_IN1, LMOTOR_IN2}, // LEFT_MOTOR Pins
|
||||||
|
{ARM_IN1, ARM_IN2}, //ARM_MOTOR pins
|
||||||
|
};
|
||||||
|
|
||||||
|
#define NUMMOTORS 3
|
||||||
|
motor motors[NUMMOTORS];
|
||||||
|
|
||||||
|
void setupmotors()
|
||||||
|
{
|
||||||
|
|
||||||
|
for (int i = 0; i < NUMMOTORS; i++)
|
||||||
|
{
|
||||||
|
motors[i].init(motorPins[i].pinIN1, motorPins[i].pinIN2, i+2, false); // pinMode(motorPins[i].pinIN1, OUTPUT);
|
||||||
|
motors[i].stop();
|
||||||
|
motors[i].setindex(i);
|
||||||
|
log_i("motor(%d) initialized", i);
|
||||||
|
delay(50);
|
||||||
|
}
|
||||||
|
bucketServo.attach(bucketServoPin);
|
||||||
|
bucketServo.write(default_bucketTilt);
|
||||||
|
//auxServo.attach(auxServoPin);
|
||||||
|
//auxControl(default_auxControl);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t lastmotorlog = 0;
|
||||||
|
|
||||||
|
void drivemotor(uint8_t num, int dirspeed)
|
||||||
|
{
|
||||||
|
if (num <= motorPins.size())
|
||||||
|
{
|
||||||
|
if(dirspeed > 46 && dirspeed < 55) //deadband
|
||||||
|
{
|
||||||
|
motors[num].stop();
|
||||||
|
log_v("stop");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
uint8_t mapspeed = map(dirspeed, 0, 100, 100, -100);
|
||||||
|
motors[num].move(mapspeed);
|
||||||
|
motors[num].prevsetpoint = mapspeed;
|
||||||
|
if (millis() - lastmotorlog > MOTORLOGTIME)
|
||||||
|
{
|
||||||
|
log_i("drive motor %u, speed %d%(%d)", num, dirspeed, mapspeed);
|
||||||
|
lastmotorlog = millis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
log_e("invalid motor num %d", num);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int prevBucketAngle = 0;
|
||||||
|
uint32_t lastbuckettimer = 0;
|
||||||
|
void bucketTilt(int bucketServoValue)
|
||||||
|
{
|
||||||
|
if(millis()- lastbuckettimer > BUCKETTIMER)
|
||||||
|
{
|
||||||
|
log_v("bucket command received = %i", bucketServoValue);
|
||||||
|
int servo = 0;
|
||||||
|
if(bucketServoValue == 0)
|
||||||
|
{
|
||||||
|
log_v("bucket stop");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else if(bucketServoValue > 0)
|
||||||
|
{
|
||||||
|
servo = prevBucketAngle + SERVOSTEP;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
servo = prevBucketAngle - SERVOSTEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(servo > SERVOMAX) servo = SERVOMAX;
|
||||||
|
if(servo < SERVOMIN) servo = SERVOMIN;
|
||||||
|
|
||||||
|
bucketServo.write(servo);
|
||||||
|
log_v("bucket (%i) angle=(%d)", bucketServoValue, servo);
|
||||||
|
|
||||||
|
lastbuckettimer = millis();
|
||||||
|
prevBucketAngle = servo;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void AbsBucketTilt(int bucketServoValue)
|
||||||
|
{
|
||||||
|
log_v("drive bucket servo, angle %d", bucketServoValue);
|
||||||
|
delay(5);
|
||||||
|
bucketServo.write(bucketServoValue);
|
||||||
|
}
|
||||||
|
|
||||||
|
void auxControl(int auxServoValue)
|
||||||
|
{
|
||||||
|
log_v("drive aux servo, angle %d", auxServoValue);
|
||||||
|
delay(5);
|
||||||
|
auxServo.write(auxServoValue);
|
||||||
|
}
|
||||||
21
Miniskid/FW/src/config.h
Executable file
21
Miniskid/FW/src/config.h
Executable file
@@ -0,0 +1,21 @@
|
|||||||
|
//config
|
||||||
|
|
||||||
|
|
||||||
|
//Pin configuration
|
||||||
|
#define RMOTOR_IN1 32
|
||||||
|
#define RMOTOR_IN2 33
|
||||||
|
#define LMOTOR_IN1 26
|
||||||
|
#define LMOTOR_IN2 25
|
||||||
|
#define ARM_IN1 19
|
||||||
|
#define ARM_IN2 22
|
||||||
|
|
||||||
|
#define bucketServoPin 23
|
||||||
|
#define auxServoPin 17
|
||||||
|
|
||||||
|
//defaults
|
||||||
|
|
||||||
|
#define default_auxControl 150
|
||||||
|
#define default_bucketTilt 200
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
65
Miniskid/FW/src/controller.cpp
Executable file
65
Miniskid/FW/src/controller.cpp
Executable file
@@ -0,0 +1,65 @@
|
|||||||
|
#include "controller.h"
|
||||||
|
|
||||||
|
XboxSeriesXControllerESP32_asukiaaa::Core xboxController; //"40:8e:2c:41:e4:eb"); //("a4:c1:38:38:e3:c0");
|
||||||
|
uint32_t lastcontrollernotify = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void setup_controller()
|
||||||
|
{
|
||||||
|
xboxController.begin();
|
||||||
|
xboxController.onLoop();
|
||||||
|
Serial.printf("Waiting for controller");
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop_controller()
|
||||||
|
{
|
||||||
|
|
||||||
|
xboxController.onLoop();
|
||||||
|
if (xboxController.isConnected())
|
||||||
|
{
|
||||||
|
if (xboxController.isWaitingForFirstNotification())
|
||||||
|
{
|
||||||
|
Serial.println("waiting for first notification");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
log_v("Address: %s", xboxController.buildDeviceAddressStr());
|
||||||
|
// log_i("message: %s", Serial.print(xboxController.xboxNotif.toString()));
|
||||||
|
unsigned long receivedAt = xboxController.getReceiveNotificationAt();
|
||||||
|
uint16_t joystickMax = XboxControllerNotificationParser::maxJoy;
|
||||||
|
if (millis() - lastcontrollernotify > CONTROLLERNOTIFY)
|
||||||
|
{
|
||||||
|
log_i("joyLHori rate: %0.0f", ((float)xboxController.xboxNotif.joyLHori / joystickMax *100));
|
||||||
|
log_i("joyLVert rate: %0.0f",((float)xboxController.xboxNotif.joyLVert / joystickMax *100));
|
||||||
|
log_i("joyRHori rate: %0.0f", ((float)xboxController.xboxNotif.joyRHori / joystickMax *100));
|
||||||
|
log_i("joyRVert rate: %0.0f",((float)xboxController.xboxNotif.joyRVert / joystickMax *100));
|
||||||
|
log_i("battery %d %", xboxController.battery);
|
||||||
|
log_i("received at %l", receivedAt);
|
||||||
|
lastcontrollernotify = millis();
|
||||||
|
}
|
||||||
|
handle_notify(((float)xboxController.xboxNotif.joyLVert / joystickMax *100),
|
||||||
|
((float)xboxController.xboxNotif.joyRVert / joystickMax *100),
|
||||||
|
((float)xboxController.xboxNotif.joyLHori / joystickMax *100),
|
||||||
|
((float)xboxController.xboxNotif.joyRHori / joystickMax *100)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
log_w("not connected");
|
||||||
|
if (xboxController.getCountFailedConnection() > 10)
|
||||||
|
{
|
||||||
|
log_e("restarting");
|
||||||
|
ESP.restart();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handle_notify(int motR, int motL, int motArm, int bucket)
|
||||||
|
{
|
||||||
|
drivemotor(0, motR);
|
||||||
|
drivemotor(1, motL);
|
||||||
|
drivemotor(2, motArm);
|
||||||
|
bucketTilt(bucket);
|
||||||
|
}
|
||||||
10
Miniskid/FW/src/controller.h
Executable file
10
Miniskid/FW/src/controller.h
Executable file
@@ -0,0 +1,10 @@
|
|||||||
|
#include "Arduino.h"
|
||||||
|
#include <XboxSeriesXControllerESP32_asukiaaa.hpp>
|
||||||
|
#include "motors.h"
|
||||||
|
|
||||||
|
#define CONTROLLERNOTIFY 1000
|
||||||
|
|
||||||
|
void setup_controller();
|
||||||
|
void loop_controller();
|
||||||
|
void handle_notify(int motR, int motL, int motArm, int bucket);
|
||||||
|
|
||||||
22
Miniskid/FW/src/main.cpp
Executable file
22
Miniskid/FW/src/main.cpp
Executable file
@@ -0,0 +1,22 @@
|
|||||||
|
//make sure to upload with ESP32 Dev Module selected as the board under tools>Board>ESP32 Arduino
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "motors.h"
|
||||||
|
#include "controller.h"
|
||||||
|
|
||||||
|
void setup(void)
|
||||||
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
delay(1000);
|
||||||
|
log_i("init hardware");
|
||||||
|
|
||||||
|
setup_controller();
|
||||||
|
|
||||||
|
setupmotors();
|
||||||
|
// setup_webserver();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
loop_controller();
|
||||||
|
}
|
||||||
61
Miniskid/FW/src/motors.h
Executable file
61
Miniskid/FW/src/motors.h
Executable file
@@ -0,0 +1,61 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <vector>
|
||||||
|
//#include "ESP32MotorControl.h"
|
||||||
|
#include "Cdrv8833.h"
|
||||||
|
|
||||||
|
#include <ESP32Servo.h> //by Kevin Harrington
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
|
||||||
|
#define RIGHT_MOTOR 1
|
||||||
|
#define LEFT_MOTOR 0
|
||||||
|
#define ARM_MOTOR 2
|
||||||
|
|
||||||
|
|
||||||
|
#define SERVOSTEP 10
|
||||||
|
#define SERVOMIN 50
|
||||||
|
#define SERVOMAX 180
|
||||||
|
|
||||||
|
#define BUCKETTIMER 10
|
||||||
|
|
||||||
|
#define MOTORLOGTIME 1000
|
||||||
|
|
||||||
|
struct MOTOR_PINS
|
||||||
|
{
|
||||||
|
int pinIN1;
|
||||||
|
int pinIN2;
|
||||||
|
};
|
||||||
|
|
||||||
|
//general functions
|
||||||
|
void setupmotors();
|
||||||
|
void loop_motors();
|
||||||
|
|
||||||
|
void drivemotor(uint8_t num, int dirspeed);
|
||||||
|
|
||||||
|
|
||||||
|
//Servo functions
|
||||||
|
void bucketTilt(int bucketServoValue);
|
||||||
|
void auxControl(int auxServoValue);
|
||||||
|
void AbsBucketTilt(int bucketServoValue);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
class motor: public Cdrv8833
|
||||||
|
{
|
||||||
|
const uint8_t motorindex = 0;
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
uint8_t m_index;
|
||||||
|
int prevsetpoint = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void drive(int dirspeed);
|
||||||
|
void setindex(uint8_t index)
|
||||||
|
{
|
||||||
|
m_index = index;
|
||||||
|
}
|
||||||
|
};
|
||||||
11
Miniskid/FW/test/README
Executable file
11
Miniskid/FW/test/README
Executable file
@@ -0,0 +1,11 @@
|
|||||||
|
|
||||||
|
This directory is intended for PlatformIO Test Runner and project tests.
|
||||||
|
|
||||||
|
Unit Testing is a software testing method by which individual units of
|
||||||
|
source code, sets of one or more MCU program modules together with associated
|
||||||
|
control data, usage procedures, and operating procedures, are tested to
|
||||||
|
determine whether they are fit for use. Unit testing finds problems early
|
||||||
|
in the development cycle.
|
||||||
|
|
||||||
|
More information about PlatformIO Unit Testing:
|
||||||
|
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html
|
||||||
BIN
Miniskid/SCH/miniskidi/miniskidi-backups/miniskidi-2023-11-05_125438.zip
Executable file
BIN
Miniskid/SCH/miniskidi/miniskidi-backups/miniskidi-2023-11-05_125438.zip
Executable file
Binary file not shown.
BIN
Miniskid/SCH/miniskidi/miniskidi-backups/miniskidi-2023-11-05_125953.zip
Executable file
BIN
Miniskid/SCH/miniskidi/miniskidi-backups/miniskidi-2023-11-05_125953.zip
Executable file
Binary file not shown.
2
Miniskid/SCH/miniskidi/miniskidi.kicad_pcb
Executable file
2
Miniskid/SCH/miniskidi/miniskidi.kicad_pcb
Executable file
@@ -0,0 +1,2 @@
|
|||||||
|
(kicad_pcb (version 20221018) (generator pcbnew)
|
||||||
|
)
|
||||||
332
Miniskid/SCH/miniskidi/miniskidi.kicad_pro
Executable file
332
Miniskid/SCH/miniskidi/miniskidi.kicad_pro
Executable file
@@ -0,0 +1,332 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"3dviewports": [],
|
||||||
|
"design_settings": {
|
||||||
|
"defaults": {
|
||||||
|
"board_outline_line_width": 0.1,
|
||||||
|
"copper_line_width": 0.2,
|
||||||
|
"copper_text_size_h": 1.5,
|
||||||
|
"copper_text_size_v": 1.5,
|
||||||
|
"copper_text_thickness": 0.3,
|
||||||
|
"other_line_width": 0.15,
|
||||||
|
"silk_line_width": 0.15,
|
||||||
|
"silk_text_size_h": 1.0,
|
||||||
|
"silk_text_size_v": 1.0,
|
||||||
|
"silk_text_thickness": 0.15
|
||||||
|
},
|
||||||
|
"diff_pair_dimensions": [],
|
||||||
|
"drc_exclusions": [],
|
||||||
|
"rules": {
|
||||||
|
"min_copper_edge_clearance": 0.0,
|
||||||
|
"solder_mask_clearance": 0.0,
|
||||||
|
"solder_mask_min_width": 0.0
|
||||||
|
},
|
||||||
|
"track_widths": [],
|
||||||
|
"via_dimensions": []
|
||||||
|
},
|
||||||
|
"layer_presets": [],
|
||||||
|
"viewports": []
|
||||||
|
},
|
||||||
|
"boards": [],
|
||||||
|
"cvpcb": {
|
||||||
|
"equivalence_files": []
|
||||||
|
},
|
||||||
|
"erc": {
|
||||||
|
"erc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"pin_map": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"rule_severities": {
|
||||||
|
"bus_definition_conflict": "error",
|
||||||
|
"bus_entry_needed": "error",
|
||||||
|
"bus_to_bus_conflict": "error",
|
||||||
|
"bus_to_net_conflict": "error",
|
||||||
|
"conflicting_netclasses": "error",
|
||||||
|
"different_unit_footprint": "error",
|
||||||
|
"different_unit_net": "error",
|
||||||
|
"duplicate_reference": "error",
|
||||||
|
"duplicate_sheet_names": "error",
|
||||||
|
"endpoint_off_grid": "warning",
|
||||||
|
"extra_units": "error",
|
||||||
|
"global_label_dangling": "warning",
|
||||||
|
"hier_label_mismatch": "error",
|
||||||
|
"label_dangling": "error",
|
||||||
|
"lib_symbol_issues": "warning",
|
||||||
|
"missing_bidi_pin": "warning",
|
||||||
|
"missing_input_pin": "warning",
|
||||||
|
"missing_power_pin": "error",
|
||||||
|
"missing_unit": "warning",
|
||||||
|
"multiple_net_names": "warning",
|
||||||
|
"net_not_bus_member": "warning",
|
||||||
|
"no_connect_connected": "warning",
|
||||||
|
"no_connect_dangling": "warning",
|
||||||
|
"pin_not_connected": "error",
|
||||||
|
"pin_not_driven": "error",
|
||||||
|
"pin_to_pin": "warning",
|
||||||
|
"power_pin_not_driven": "error",
|
||||||
|
"similar_labels": "warning",
|
||||||
|
"simulation_model_issue": "error",
|
||||||
|
"unannotated": "error",
|
||||||
|
"unit_value_mismatch": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"wire_dangling": "error"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"libraries": {
|
||||||
|
"pinned_footprint_libs": [],
|
||||||
|
"pinned_symbol_libs": []
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "miniskidi.kicad_pro",
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_settings": {
|
||||||
|
"classes": [
|
||||||
|
{
|
||||||
|
"bus_width": 12,
|
||||||
|
"clearance": 0.2,
|
||||||
|
"diff_pair_gap": 0.25,
|
||||||
|
"diff_pair_via_gap": 0.25,
|
||||||
|
"diff_pair_width": 0.2,
|
||||||
|
"line_style": 0,
|
||||||
|
"microvia_diameter": 0.3,
|
||||||
|
"microvia_drill": 0.1,
|
||||||
|
"name": "Default",
|
||||||
|
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"track_width": 0.25,
|
||||||
|
"via_diameter": 0.8,
|
||||||
|
"via_drill": 0.4,
|
||||||
|
"wire_width": 6
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"meta": {
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"net_colors": null,
|
||||||
|
"netclass_assignments": null,
|
||||||
|
"netclass_patterns": []
|
||||||
|
},
|
||||||
|
"pcbnew": {
|
||||||
|
"last_paths": {
|
||||||
|
"gencad": "",
|
||||||
|
"idf": "",
|
||||||
|
"netlist": "",
|
||||||
|
"specctra_dsn": "",
|
||||||
|
"step": "",
|
||||||
|
"vrml": ""
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": ""
|
||||||
|
},
|
||||||
|
"schematic": {
|
||||||
|
"annotate_start_num": 0,
|
||||||
|
"drawing": {
|
||||||
|
"dashed_lines_dash_length_ratio": 12.0,
|
||||||
|
"dashed_lines_gap_length_ratio": 3.0,
|
||||||
|
"default_line_thickness": 6.0,
|
||||||
|
"default_text_size": 50.0,
|
||||||
|
"field_names": [],
|
||||||
|
"intersheets_ref_own_page": false,
|
||||||
|
"intersheets_ref_prefix": "",
|
||||||
|
"intersheets_ref_short": false,
|
||||||
|
"intersheets_ref_show": false,
|
||||||
|
"intersheets_ref_suffix": "",
|
||||||
|
"junction_size_choice": 3,
|
||||||
|
"label_size_ratio": 0.375,
|
||||||
|
"pin_symbol_size": 25.0,
|
||||||
|
"text_offset_ratio": 0.15
|
||||||
|
},
|
||||||
|
"legacy_lib_dir": "",
|
||||||
|
"legacy_lib_list": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_format_name": "",
|
||||||
|
"page_layout_descr_file": "",
|
||||||
|
"plot_directory": "",
|
||||||
|
"spice_current_sheet_as_root": false,
|
||||||
|
"spice_external_command": "spice \"%I\"",
|
||||||
|
"spice_model_current_sheet_as_root": true,
|
||||||
|
"spice_save_all_currents": false,
|
||||||
|
"spice_save_all_voltages": false,
|
||||||
|
"subpart_first_id": 65,
|
||||||
|
"subpart_id_separator": 0
|
||||||
|
},
|
||||||
|
"sheets": [
|
||||||
|
[
|
||||||
|
"1b5c276f-c8a9-496b-981d-1974f4678c8d",
|
||||||
|
""
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"text_variables": {}
|
||||||
|
}
|
||||||
1634
Miniskid/SCH/miniskidi/miniskidi.kicad_sch
Executable file
1634
Miniskid/SCH/miniskidi/miniskidi.kicad_sch
Executable file
File diff suppressed because it is too large
Load Diff
@@ -17,3 +17,7 @@ lib_deps =
|
|||||||
asukiaaa/XboxSeriesXControllerESP32_asukiaaa @ ^1.0.9
|
asukiaaa/XboxSeriesXControllerESP32_asukiaaa @ ^1.0.9
|
||||||
adafruit/Adafruit MCP23017 Arduino Library @ ^2.3.2
|
adafruit/Adafruit MCP23017 Arduino Library @ ^2.3.2
|
||||||
madhephaestus/ESP32Servo @ ^3.0.5
|
madhephaestus/ESP32Servo @ ^3.0.5
|
||||||
|
build_flags =
|
||||||
|
-DCORE_DEBUG_LEVEL=3
|
||||||
|
-DNDEF_DEBUG=1
|
||||||
|
-fexceptions
|
||||||
@@ -3,25 +3,80 @@
|
|||||||
XboxSeriesXControllerESP32_asukiaaa::Core xboxController; //"40:8e:2c:41:e4:eb"); //("a4:c1:38:38:e3:c0");
|
XboxSeriesXControllerESP32_asukiaaa::Core xboxController; //"40:8e:2c:41:e4:eb"); //("a4:c1:38:38:e3:c0");
|
||||||
uint32_t lastcontrollernotify = 0;
|
uint32_t lastcontrollernotify = 0;
|
||||||
|
|
||||||
int joymin = 0;
|
uint16_t joymax = 0;
|
||||||
int joymax = 0;
|
uint16_t trgmax = 0;
|
||||||
|
#define deadband 20000
|
||||||
|
#define trgdeadband 200
|
||||||
|
bool cablights = false;
|
||||||
|
|
||||||
|
direction getdirectionJoy(int setpoint)
|
||||||
direction getdirection(int setpoint)
|
|
||||||
{
|
{
|
||||||
if(setpoint > )
|
if (setpoint > (joymax / 2 + deadband))
|
||||||
|
{
|
||||||
|
return direction::right;
|
||||||
|
}
|
||||||
|
else if (setpoint < (joymax / 2 - deadband))
|
||||||
|
{
|
||||||
|
return direction::left;
|
||||||
|
}
|
||||||
|
// else
|
||||||
|
return direction::stop;
|
||||||
|
}
|
||||||
|
|
||||||
|
direction getdirecion2Button(uint8_t button0, uint8_t button1)
|
||||||
|
{
|
||||||
|
if (button0 & !button1)
|
||||||
|
{
|
||||||
|
return direction::left;
|
||||||
|
}
|
||||||
|
if (!button0 & button1)
|
||||||
|
{
|
||||||
|
return direction::right;
|
||||||
|
}
|
||||||
|
// else
|
||||||
|
return direction::stop;
|
||||||
|
}
|
||||||
|
|
||||||
|
direction getTrackDirection(int trigger, uint8_t shoulder)
|
||||||
|
{
|
||||||
|
if (trigger > (trgmax / 2 + trgdeadband) & !shoulder)
|
||||||
|
{
|
||||||
|
return direction::right;
|
||||||
|
}
|
||||||
|
if ((trigger == 0) & shoulder)
|
||||||
|
{
|
||||||
|
return direction::left;
|
||||||
|
}
|
||||||
|
return direction::stop;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_controller()
|
void setup_controller()
|
||||||
{
|
{
|
||||||
xboxController.begin();
|
xboxController.begin();
|
||||||
xboxController.onLoop();
|
xboxController.onLoop();
|
||||||
|
xboxController.startScan();
|
||||||
|
|
||||||
Serial.printf("Waiting for controller");
|
Serial.printf("Waiting for controller");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop_controller()
|
void handleCabLights(uint8_t button)
|
||||||
{
|
{
|
||||||
|
if(!button) return;
|
||||||
|
|
||||||
|
if (cablights)
|
||||||
|
{
|
||||||
|
digitalWrite(cabLights, HIGH);
|
||||||
|
cablights = true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
digitalWrite(cabLights, LOW);
|
||||||
|
cablights = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop_controller()
|
||||||
|
{
|
||||||
xboxController.onLoop();
|
xboxController.onLoop();
|
||||||
if (xboxController.isConnected())
|
if (xboxController.isConnected())
|
||||||
{
|
{
|
||||||
@@ -34,35 +89,42 @@ void loop_controller()
|
|||||||
log_v("Address: %s", xboxController.buildDeviceAddressStr());
|
log_v("Address: %s", xboxController.buildDeviceAddressStr());
|
||||||
// log_i("message: %s", Serial.print(xboxController.xboxNotif.toString()));
|
// log_i("message: %s", Serial.print(xboxController.xboxNotif.toString()));
|
||||||
unsigned long receivedAt = xboxController.getReceiveNotificationAt();
|
unsigned long receivedAt = xboxController.getReceiveNotificationAt();
|
||||||
uint16_t joystickMax = XboxControllerNotificationParser::maxJoy;
|
joymax = XboxControllerNotificationParser::maxJoy;
|
||||||
|
trgmax = XboxControllerNotificationParser::maxTrig;
|
||||||
if (millis() - lastcontrollernotify > CONTROLLERNOTIFY)
|
if (millis() - lastcontrollernotify > CONTROLLERNOTIFY)
|
||||||
{
|
{
|
||||||
log_i("joyLHori rate: %0.0f", ((float)xboxController.xboxNotif.joyLHori / joystickMax *100));
|
// log_i("joyLHori rate: %u", xboxController.xboxNotif.btnLS);
|
||||||
log_i("joyLVert rate: %0.0f",((float)xboxController.xboxNotif.joyLVert / joystickMax *100));
|
// log_i("joyLVert rate: %u", xboxController.xboxNotif.btnLB);
|
||||||
log_i("joyRHori rate: %0.0f", ((float)xboxController.xboxNotif.joyRHori / joystickMax *100));
|
// log_i("joyRHori rate: %u", xboxController.xboxNotif.trigLT);
|
||||||
log_i("joyRVert rate: %0.0f",((float)xboxController.xboxNotif.joyRVert / joystickMax *100));
|
// log_i("joyRVert rate: %u", xboxController.xboxNotif.trigRT);
|
||||||
log_i("battery %d %", xboxController.battery);
|
log_i("battery %d %", xboxController.battery);
|
||||||
log_i("received at %l", receivedAt);
|
// log_v("joymax:%d",joymax );
|
||||||
lastcontrollernotify = millis();
|
lastcontrollernotify = millis();
|
||||||
}
|
}
|
||||||
controlMotor("mainboom", direction::stop)
|
controlMotor("Pivot", getdirectionJoy(xboxController.xboxNotif.joyLHori));
|
||||||
|
controlMotor("Dipper", getdirectionJoy(xboxController.xboxNotif.joyLVert));
|
||||||
|
controlMotor("Bucket", getdirectionJoy(xboxController.xboxNotif.joyRHori));
|
||||||
|
controlMotor("Boom", getdirectionJoy(xboxController.xboxNotif.joyRVert));
|
||||||
|
controlMotor("Push", getdirecion2Button(xboxController.xboxNotif.btnX, xboxController.xboxNotif.btnY));
|
||||||
|
controlMotor("Thumb", getdirecion2Button(xboxController.xboxNotif.btnA, xboxController.xboxNotif.btnB));
|
||||||
|
|
||||||
|
controlMotor("TrackLeft", getTrackDirection(xboxController.xboxNotif.trigLT, xboxController.xboxNotif.btnLB));
|
||||||
|
controlMotor("TrackRight", getTrackDirection(xboxController.xboxNotif.trigRT, xboxController.xboxNotif.btnRB));
|
||||||
|
handleCabLights(xboxController.xboxNotif.btnShare);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
{
|
||||||
|
if (millis() - lastcontrollernotify > CONTROLLERNOTIFY)
|
||||||
{
|
{
|
||||||
log_w("not connected");
|
log_w("not connected");
|
||||||
|
lastcontrollernotify = millis();
|
||||||
|
handleCabLights(1);
|
||||||
|
}
|
||||||
if (xboxController.getCountFailedConnection() > 10)
|
if (xboxController.getCountFailedConnection() > 10)
|
||||||
{
|
{
|
||||||
log_e("restarting");
|
log_e("restarting");
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void handle_notify(int motR, int motL, int motArm, int bucket)
|
|
||||||
{
|
|
||||||
drivemotor(0, motR);
|
|
||||||
drivemotor(1, motL);
|
|
||||||
drivemotor(2, motArm);
|
|
||||||
bucketTilt(bucket);
|
|
||||||
}
|
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
#include "motors.h"
|
#include "motors.h"
|
||||||
#include <XboxSeriesXControllerESP32_asukiaaa.hpp>
|
#include <XboxSeriesXControllerESP32_asukiaaa.hpp>
|
||||||
|
|
||||||
#define CONTROLLERNOTIFY 1000
|
#define CONTROLLERNOTIFY 30000
|
||||||
|
|
||||||
|
|
||||||
void setup_controller();
|
void setup_controller();
|
||||||
|
|||||||
@@ -9,22 +9,7 @@ void setup() {
|
|||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
// Ps3.attach(notify);
|
setup_motors();
|
||||||
// Ps3.attachOnConnect(onConnect);
|
|
||||||
// Ps3.begin("a0:5a:5a:a0:0f:91");
|
|
||||||
|
|
||||||
// Serial.println("Ready.");
|
|
||||||
|
|
||||||
// pinMode(clawServoPin, OUTPUT);
|
|
||||||
// pinMode(auxServoPin, OUTPUT);
|
|
||||||
|
|
||||||
// pinMode(cabLights, OUTPUT);
|
|
||||||
// pinMode(auxLights, OUTPUT);
|
|
||||||
|
|
||||||
// clawServo.attach(clawServoPin);
|
|
||||||
// auxServo.attach(auxServoPin);
|
|
||||||
// clawServo.write(clawServoValue);
|
|
||||||
// auxServo.write(auxServoValue);
|
|
||||||
setup_controller();
|
setup_controller();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -11,14 +11,14 @@ Servo auxServo;
|
|||||||
|
|
||||||
motorinit initlist[NUMMOTORS]
|
motorinit initlist[NUMMOTORS]
|
||||||
{
|
{
|
||||||
{pivot0, pivot1, 0, "Pivot"},
|
{pivot0, pivot1, 0, "Pivot", true},
|
||||||
{mainBoom0, mainBoom1, 1, "Boom"},
|
{mainBoom0, mainBoom1, 1, "Boom", false},
|
||||||
{secondBoom0, secondBoom1, 2, "Dipper"},
|
{secondBoom0, secondBoom1, 2, "Dipper", true},
|
||||||
{tiltAttach0, tiltAttach1, 3, "Bucket"},
|
{tiltAttach0, tiltAttach1, 3, "Bucket", true},
|
||||||
{thumb0, thumb1, 4, "Thumb"},
|
{thumb0, thumb1, 4, "Thumb", false},
|
||||||
{auxAttach0, auxAttach1, 5, "Aux"},
|
{auxAttach0, auxAttach1, 5, "Push", false},
|
||||||
{leftMotor0, leftMotor1, 6, "TrackLeft"},
|
{leftMotor0, leftMotor1, 6, "TrackLeft", true},
|
||||||
{rightMotor0, rightMotor1, 7, "TrackRight"}
|
{rightMotor0, rightMotor1, 7, "TrackRight", true}
|
||||||
};
|
};
|
||||||
|
|
||||||
std::vector<motor> motors;
|
std::vector<motor> motors;
|
||||||
@@ -26,6 +26,7 @@ std::vector<motor> motors;
|
|||||||
|
|
||||||
void setup_motors()
|
void setup_motors()
|
||||||
{
|
{
|
||||||
|
mcp.begin_I2C();
|
||||||
for (int i = 0; i < NUMMOTORS; i++)
|
for (int i = 0; i < NUMMOTORS; i++)
|
||||||
{
|
{
|
||||||
motor newmotor(initlist[i]);
|
motor newmotor(initlist[i]);
|
||||||
@@ -51,8 +52,10 @@ void controlMotor(String name, direction dir)
|
|||||||
if(thismotor.getName() == name)
|
if(thismotor.getName() == name)
|
||||||
{
|
{
|
||||||
thismotor.run(dir);
|
thismotor.run(dir);
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
log_e("motor %s not found",name);
|
||||||
}
|
}
|
||||||
|
|
||||||
void motor::begin()
|
void motor::begin()
|
||||||
@@ -64,8 +67,28 @@ void motor::begin()
|
|||||||
|
|
||||||
void motor::setIO(uint8_t in0, uint8_t in1)
|
void motor::setIO(uint8_t in0, uint8_t in1)
|
||||||
{
|
{
|
||||||
|
if(!m_invert)
|
||||||
|
{
|
||||||
mcp.digitalWrite(m_pin0, in0);
|
mcp.digitalWrite(m_pin0, in0);
|
||||||
mcp.digitalWrite(m_pin1, in1);
|
mcp.digitalWrite(m_pin1, in1);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
mcp.digitalWrite(m_pin0, in1);
|
||||||
|
mcp.digitalWrite(m_pin1, in0);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t lastmotorlog = 0;
|
||||||
|
|
||||||
|
void logactions(String dir, String name)
|
||||||
|
{
|
||||||
|
if (millis() - lastmotorlog > MOTORLOGTIME)
|
||||||
|
{
|
||||||
|
log_i("motor %s: %s", name, dir);
|
||||||
|
lastmotorlog = millis();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void motor::run(direction dir)
|
void motor::run(direction dir)
|
||||||
@@ -77,98 +100,23 @@ void motor::run(direction dir)
|
|||||||
case direction::left:
|
case direction::left:
|
||||||
{
|
{
|
||||||
setIO(HIGH, LOW);
|
setIO(HIGH, LOW);
|
||||||
|
log_i("motor %s: left", getName());
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case direction::right:
|
case direction::right:
|
||||||
{
|
{
|
||||||
setIO(LOW, HIGH);
|
setIO(LOW, HIGH);
|
||||||
|
log_i("motor %s: Right", getName());
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case direction::stop:
|
case direction::stop:
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
setIO(LOW, LOW);
|
setIO(LOW, LOW);
|
||||||
|
log_i("motor %s: stop", getName());
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
current = dir;
|
current = dir;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//uint32_t lastmotorlog = 0;
|
|
||||||
|
|
||||||
|
|
||||||
// void drivemotor(uint8_t num, int dirspeed)
|
|
||||||
// {
|
|
||||||
// if (num <= motorPins.size())
|
|
||||||
// {
|
|
||||||
// if(dirspeed > 46 && dirspeed < 55) //deadband
|
|
||||||
// {
|
|
||||||
// motors[num].stop();
|
|
||||||
// log_v("stop");
|
|
||||||
// return;
|
|
||||||
// }
|
|
||||||
// else
|
|
||||||
// {
|
|
||||||
// uint8_t mapspeed = map(dirspeed, 0, 100, 100, -100);
|
|
||||||
// motors[num].move(mapspeed);
|
|
||||||
// motors[num].prevsetpoint = mapspeed;
|
|
||||||
// if (millis() - lastmotorlog > MOTORLOGTIME)
|
|
||||||
// {
|
|
||||||
// log_i("drive motor %u, speed %d%(%d)", num, dirspeed, mapspeed);
|
|
||||||
// lastmotorlog = millis();
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// else
|
|
||||||
// {
|
|
||||||
// log_e("invalid motor num %d", num);
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
|
|
||||||
// int prevBucketAngle = 0;
|
|
||||||
// uint32_t lastbuckettimer = 0;
|
|
||||||
// void bucketTilt(int bucketServoValue)
|
|
||||||
// {
|
|
||||||
// if(millis()- lastbuckettimer > BUCKETTIMER)
|
|
||||||
// {
|
|
||||||
// log_v("bucket command received = %i", bucketServoValue);
|
|
||||||
// int servo = 0;
|
|
||||||
// if(bucketServoValue == 0)
|
|
||||||
// {
|
|
||||||
// log_v("bucket stop");
|
|
||||||
// return;
|
|
||||||
// }
|
|
||||||
// else if(bucketServoValue > 0)
|
|
||||||
// {
|
|
||||||
// servo = prevBucketAngle + SERVOSTEP;
|
|
||||||
// }
|
|
||||||
// else
|
|
||||||
// {
|
|
||||||
// servo = prevBucketAngle - SERVOSTEP;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// if(servo > SERVOMAX) servo = SERVOMAX;
|
|
||||||
// if(servo < SERVOMIN) servo = SERVOMIN;
|
|
||||||
|
|
||||||
// bucketServo.write(servo);
|
|
||||||
// log_v("bucket (%i) angle=(%d)", bucketServoValue, servo);
|
|
||||||
|
|
||||||
// lastbuckettimer = millis();
|
|
||||||
// prevBucketAngle = servo;
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
|
|
||||||
// void AbsBucketTilt(int bucketServoValue)
|
|
||||||
// {
|
|
||||||
// log_v("drive bucket servo, angle %d", bucketServoValue);
|
|
||||||
// delay(5);
|
|
||||||
// bucketServo.write(bucketServoValue);
|
|
||||||
// }
|
|
||||||
|
|
||||||
// void auxControl(int auxServoValue)
|
|
||||||
// {
|
|
||||||
// log_v("drive aux servo, angle %d", auxServoValue);
|
|
||||||
// delay(5);
|
|
||||||
// auxServo.write(auxServoValue);
|
|
||||||
// }
|
|
||||||
|
|||||||
@@ -17,9 +17,7 @@
|
|||||||
#define MOTORLOGTIME 1000
|
#define MOTORLOGTIME 1000
|
||||||
|
|
||||||
|
|
||||||
//general functions
|
|
||||||
void setup_motors();
|
|
||||||
void controlMotor(String name, direction dir);
|
|
||||||
|
|
||||||
struct motorinit
|
struct motorinit
|
||||||
{
|
{
|
||||||
@@ -27,6 +25,7 @@ struct motorinit
|
|||||||
uint8_t in1;
|
uint8_t in1;
|
||||||
uint8_t id;
|
uint8_t id;
|
||||||
String name;
|
String name;
|
||||||
|
bool invert;
|
||||||
};
|
};
|
||||||
|
|
||||||
enum direction
|
enum direction
|
||||||
@@ -36,6 +35,9 @@ enum direction
|
|||||||
stop
|
stop
|
||||||
};
|
};
|
||||||
|
|
||||||
|
//general functions
|
||||||
|
void setup_motors();
|
||||||
|
void controlMotor(String name, direction dir);
|
||||||
|
|
||||||
class motor
|
class motor
|
||||||
{
|
{
|
||||||
@@ -46,13 +48,15 @@ class motor
|
|||||||
String m_name;
|
String m_name;
|
||||||
uint32_t m_lastlog;
|
uint32_t m_lastlog;
|
||||||
direction current;
|
direction current;
|
||||||
|
bool m_invert;
|
||||||
void setIO(uint8_t in0, uint8_t in1);
|
void setIO(uint8_t in0, uint8_t in1);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
motor(motorinit initstruct): m_pin0(initstruct.in0),
|
motor(motorinit initstruct): m_pin0(initstruct.in0),
|
||||||
m_pin1(initstruct.in1),
|
m_pin1(initstruct.in1),
|
||||||
m_id(initstruct.id),
|
m_id(initstruct.id),
|
||||||
m_name(initstruct.name) {};
|
m_name(initstruct.name),
|
||||||
|
m_invert(initstruct.invert) {};
|
||||||
|
|
||||||
void begin();
|
void begin();
|
||||||
void run(direction dir);
|
void run(direction dir);
|
||||||
|
|||||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
2
RC excavator/PCB/driverboard/driverboard.kicad_pcb
Normal file
2
RC excavator/PCB/driverboard/driverboard.kicad_pcb
Normal file
@@ -0,0 +1,2 @@
|
|||||||
|
(kicad_pcb (version 20240108) (generator "pcbnew") (generator_version "8.0")
|
||||||
|
)
|
||||||
83
RC excavator/PCB/driverboard/driverboard.kicad_prl
Normal file
83
RC excavator/PCB/driverboard/driverboard.kicad_prl
Normal file
@@ -0,0 +1,83 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"active_layer": 0,
|
||||||
|
"active_layer_preset": "",
|
||||||
|
"auto_track_width": true,
|
||||||
|
"hidden_netclasses": [],
|
||||||
|
"hidden_nets": [],
|
||||||
|
"high_contrast_mode": 0,
|
||||||
|
"net_color_mode": 1,
|
||||||
|
"opacity": {
|
||||||
|
"images": 0.6,
|
||||||
|
"pads": 1.0,
|
||||||
|
"tracks": 1.0,
|
||||||
|
"vias": 1.0,
|
||||||
|
"zones": 0.6
|
||||||
|
},
|
||||||
|
"selection_filter": {
|
||||||
|
"dimensions": true,
|
||||||
|
"footprints": true,
|
||||||
|
"graphics": true,
|
||||||
|
"keepouts": true,
|
||||||
|
"lockedItems": false,
|
||||||
|
"otherItems": true,
|
||||||
|
"pads": true,
|
||||||
|
"text": true,
|
||||||
|
"tracks": true,
|
||||||
|
"vias": true,
|
||||||
|
"zones": true
|
||||||
|
},
|
||||||
|
"visible_items": [
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
3,
|
||||||
|
4,
|
||||||
|
5,
|
||||||
|
8,
|
||||||
|
9,
|
||||||
|
10,
|
||||||
|
11,
|
||||||
|
12,
|
||||||
|
13,
|
||||||
|
15,
|
||||||
|
16,
|
||||||
|
17,
|
||||||
|
18,
|
||||||
|
19,
|
||||||
|
20,
|
||||||
|
21,
|
||||||
|
22,
|
||||||
|
23,
|
||||||
|
24,
|
||||||
|
25,
|
||||||
|
26,
|
||||||
|
27,
|
||||||
|
28,
|
||||||
|
29,
|
||||||
|
30,
|
||||||
|
32,
|
||||||
|
33,
|
||||||
|
34,
|
||||||
|
35,
|
||||||
|
36,
|
||||||
|
39,
|
||||||
|
40
|
||||||
|
],
|
||||||
|
"visible_layers": "fffffff_ffffffff",
|
||||||
|
"zone_display_mode": 0
|
||||||
|
},
|
||||||
|
"git": {
|
||||||
|
"repo_password": "",
|
||||||
|
"repo_type": "",
|
||||||
|
"repo_username": "",
|
||||||
|
"ssh_key": ""
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "driverboard.kicad_prl",
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"project": {
|
||||||
|
"files": []
|
||||||
|
}
|
||||||
|
}
|
||||||
392
RC excavator/PCB/driverboard/driverboard.kicad_pro
Normal file
392
RC excavator/PCB/driverboard/driverboard.kicad_pro
Normal file
@@ -0,0 +1,392 @@
|
|||||||
|
{
|
||||||
|
"board": {
|
||||||
|
"3dviewports": [],
|
||||||
|
"design_settings": {
|
||||||
|
"defaults": {},
|
||||||
|
"diff_pair_dimensions": [],
|
||||||
|
"drc_exclusions": [],
|
||||||
|
"rules": {},
|
||||||
|
"track_widths": [],
|
||||||
|
"via_dimensions": []
|
||||||
|
},
|
||||||
|
"ipc2581": {
|
||||||
|
"dist": "",
|
||||||
|
"distpn": "",
|
||||||
|
"internal_id": "",
|
||||||
|
"mfg": "",
|
||||||
|
"mpn": ""
|
||||||
|
},
|
||||||
|
"layer_presets": [],
|
||||||
|
"viewports": []
|
||||||
|
},
|
||||||
|
"boards": [],
|
||||||
|
"cvpcb": {
|
||||||
|
"equivalence_files": []
|
||||||
|
},
|
||||||
|
"erc": {
|
||||||
|
"erc_exclusions": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 0
|
||||||
|
},
|
||||||
|
"pin_map": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
1,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
1,
|
||||||
|
0,
|
||||||
|
2,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
2
|
||||||
|
],
|
||||||
|
[
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2,
|
||||||
|
2
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"rule_severities": {
|
||||||
|
"bus_definition_conflict": "error",
|
||||||
|
"bus_entry_needed": "error",
|
||||||
|
"bus_to_bus_conflict": "error",
|
||||||
|
"bus_to_net_conflict": "error",
|
||||||
|
"conflicting_netclasses": "error",
|
||||||
|
"different_unit_footprint": "error",
|
||||||
|
"different_unit_net": "error",
|
||||||
|
"duplicate_reference": "error",
|
||||||
|
"duplicate_sheet_names": "error",
|
||||||
|
"endpoint_off_grid": "warning",
|
||||||
|
"extra_units": "error",
|
||||||
|
"global_label_dangling": "warning",
|
||||||
|
"hier_label_mismatch": "error",
|
||||||
|
"label_dangling": "error",
|
||||||
|
"lib_symbol_issues": "warning",
|
||||||
|
"missing_bidi_pin": "warning",
|
||||||
|
"missing_input_pin": "warning",
|
||||||
|
"missing_power_pin": "error",
|
||||||
|
"missing_unit": "warning",
|
||||||
|
"multiple_net_names": "warning",
|
||||||
|
"net_not_bus_member": "warning",
|
||||||
|
"no_connect_connected": "warning",
|
||||||
|
"no_connect_dangling": "warning",
|
||||||
|
"pin_not_connected": "error",
|
||||||
|
"pin_not_driven": "error",
|
||||||
|
"pin_to_pin": "warning",
|
||||||
|
"power_pin_not_driven": "error",
|
||||||
|
"similar_labels": "warning",
|
||||||
|
"simulation_model_issue": "ignore",
|
||||||
|
"unannotated": "error",
|
||||||
|
"unit_value_mismatch": "error",
|
||||||
|
"unresolved_variable": "error",
|
||||||
|
"wire_dangling": "error"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"libraries": {
|
||||||
|
"pinned_footprint_libs": [],
|
||||||
|
"pinned_symbol_libs": []
|
||||||
|
},
|
||||||
|
"meta": {
|
||||||
|
"filename": "driverboard.kicad_pro",
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_settings": {
|
||||||
|
"classes": [
|
||||||
|
{
|
||||||
|
"bus_width": 12,
|
||||||
|
"clearance": 0.2,
|
||||||
|
"diff_pair_gap": 0.25,
|
||||||
|
"diff_pair_via_gap": 0.25,
|
||||||
|
"diff_pair_width": 0.2,
|
||||||
|
"line_style": 0,
|
||||||
|
"microvia_diameter": 0.3,
|
||||||
|
"microvia_drill": 0.1,
|
||||||
|
"name": "Default",
|
||||||
|
"pcb_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"schematic_color": "rgba(0, 0, 0, 0.000)",
|
||||||
|
"track_width": 0.2,
|
||||||
|
"via_diameter": 0.6,
|
||||||
|
"via_drill": 0.3,
|
||||||
|
"wire_width": 6
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"meta": {
|
||||||
|
"version": 3
|
||||||
|
},
|
||||||
|
"net_colors": null,
|
||||||
|
"netclass_assignments": null,
|
||||||
|
"netclass_patterns": []
|
||||||
|
},
|
||||||
|
"pcbnew": {
|
||||||
|
"last_paths": {
|
||||||
|
"gencad": "",
|
||||||
|
"idf": "",
|
||||||
|
"netlist": "",
|
||||||
|
"plot": "",
|
||||||
|
"pos_files": "",
|
||||||
|
"specctra_dsn": "",
|
||||||
|
"step": "",
|
||||||
|
"svg": "",
|
||||||
|
"vrml": ""
|
||||||
|
},
|
||||||
|
"page_layout_descr_file": ""
|
||||||
|
},
|
||||||
|
"schematic": {
|
||||||
|
"annotate_start_num": 0,
|
||||||
|
"bom_export_filename": "",
|
||||||
|
"bom_fmt_presets": [],
|
||||||
|
"bom_fmt_settings": {
|
||||||
|
"field_delimiter": ",",
|
||||||
|
"keep_line_breaks": false,
|
||||||
|
"keep_tabs": false,
|
||||||
|
"name": "CSV",
|
||||||
|
"ref_delimiter": ",",
|
||||||
|
"ref_range_delimiter": "",
|
||||||
|
"string_delimiter": "\""
|
||||||
|
},
|
||||||
|
"bom_presets": [],
|
||||||
|
"bom_settings": {
|
||||||
|
"exclude_dnp": false,
|
||||||
|
"fields_ordered": [
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Reference",
|
||||||
|
"name": "Reference",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": true,
|
||||||
|
"label": "Value",
|
||||||
|
"name": "Value",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Datasheet",
|
||||||
|
"name": "Datasheet",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Footprint",
|
||||||
|
"name": "Footprint",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": false,
|
||||||
|
"label": "Qty",
|
||||||
|
"name": "${QUANTITY}",
|
||||||
|
"show": true
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"group_by": true,
|
||||||
|
"label": "DNP",
|
||||||
|
"name": "${DNP}",
|
||||||
|
"show": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"filter_string": "",
|
||||||
|
"group_symbols": true,
|
||||||
|
"name": "Grouped By Value",
|
||||||
|
"sort_asc": true,
|
||||||
|
"sort_field": "Reference"
|
||||||
|
},
|
||||||
|
"connection_grid_size": 50.0,
|
||||||
|
"drawing": {
|
||||||
|
"dashed_lines_dash_length_ratio": 12.0,
|
||||||
|
"dashed_lines_gap_length_ratio": 3.0,
|
||||||
|
"default_line_thickness": 6.0,
|
||||||
|
"default_text_size": 50.0,
|
||||||
|
"field_names": [],
|
||||||
|
"intersheets_ref_own_page": false,
|
||||||
|
"intersheets_ref_prefix": "",
|
||||||
|
"intersheets_ref_short": false,
|
||||||
|
"intersheets_ref_show": false,
|
||||||
|
"intersheets_ref_suffix": "",
|
||||||
|
"junction_size_choice": 3,
|
||||||
|
"label_size_ratio": 0.375,
|
||||||
|
"operating_point_overlay_i_precision": 3,
|
||||||
|
"operating_point_overlay_i_range": "~A",
|
||||||
|
"operating_point_overlay_v_precision": 3,
|
||||||
|
"operating_point_overlay_v_range": "~V",
|
||||||
|
"overbar_offset_ratio": 1.23,
|
||||||
|
"pin_symbol_size": 25.0,
|
||||||
|
"text_offset_ratio": 0.15
|
||||||
|
},
|
||||||
|
"legacy_lib_dir": "",
|
||||||
|
"legacy_lib_list": [],
|
||||||
|
"meta": {
|
||||||
|
"version": 1
|
||||||
|
},
|
||||||
|
"net_format_name": "",
|
||||||
|
"page_layout_descr_file": "",
|
||||||
|
"plot_directory": "",
|
||||||
|
"spice_current_sheet_as_root": false,
|
||||||
|
"spice_external_command": "spice \"%I\"",
|
||||||
|
"spice_model_current_sheet_as_root": true,
|
||||||
|
"spice_save_all_currents": false,
|
||||||
|
"spice_save_all_dissipations": false,
|
||||||
|
"spice_save_all_voltages": false,
|
||||||
|
"subpart_first_id": 65,
|
||||||
|
"subpart_id_separator": 0
|
||||||
|
},
|
||||||
|
"sheets": [
|
||||||
|
[
|
||||||
|
"24ddf3dc-32fa-47de-887e-a59bd9755857",
|
||||||
|
"Root"
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"text_variables": {}
|
||||||
|
}
|
||||||
1565
RC excavator/PCB/driverboard/driverboard.kicad_sch
Normal file
1565
RC excavator/PCB/driverboard/driverboard.kicad_sch
Normal file
File diff suppressed because it is too large
Load Diff
Reference in New Issue
Block a user