Compare commits
No commits in common. "main" and "jc" have entirely different histories.
|
@ -0,0 +1,5 @@
|
|||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
|
@ -0,0 +1,10 @@
|
|||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
],
|
||||
"unwantedRecommendations": [
|
||||
"ms-vscode.cpptools-extension-pack"
|
||||
]
|
||||
}
|
13
README.md
13
README.md
|
@ -1,13 +0,0 @@
|
|||
# USDA Pecan Embedded Software (PlatformIO)
|
||||
|
||||
This repo contains separate branches for each microcontroller to store
|
||||
the individualized software.
|
||||
|
||||
Each of:
|
||||
|
||||
- jc
|
||||
- sheller
|
||||
|
||||
Each branch implements the prerequisites for setting up a PlatformIO
|
||||
project to listen to and control equipment via MQTT, as well as
|
||||
sending back relevant diagnostic and statistical information.
|
|
@ -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
|
|
@ -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
|
|
@ -0,0 +1,20 @@
|
|||
; 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:esp32]
|
||||
platform = espressif32 @ ^6.10.0
|
||||
board = esp32dev
|
||||
framework = arduino
|
||||
lib_deps =
|
||||
FastAccelStepper
|
||||
PubSubClient
|
||||
ArduinoJson
|
||||
RotaryEncoder
|
||||
|
|
@ -0,0 +1,313 @@
|
|||
#include <Arduino.h>
|
||||
#include <FastAccelStepper.h>
|
||||
#include <WiFi.h>
|
||||
#include <PubSubClient.h>
|
||||
#include <RotaryEncoder.h>
|
||||
#include <EEPROM.h>
|
||||
|
||||
const uint8_t bottom_dir_pin = 5, top_dir_pin = 18;
|
||||
const uint8_t bottom_step_pin = 4, top_step_pin = 17;
|
||||
const uint8_t bottom_en_pin = 12, top_en_pin = 16;
|
||||
const uint8_t encoder_a = 19, encoder_b = 21;
|
||||
|
||||
#define EEPROM_SIZE 18
|
||||
#define EEPROM_BOTTOM_POS_ADDR 0
|
||||
#define EEPROM_TOP_POS_ADDR 4
|
||||
#define EEPROM_FLAG_ADDR 8
|
||||
#define EEPROM_BOTTOM_MOVING_FLAG_ADDR 9
|
||||
#define EEPROM_TOP_MOVING_FLAG_ADDR 10
|
||||
#define EEPROM_TOP_BOTTOM_DIFF_ADDR 11
|
||||
#define HOMING_FLAG 0x01
|
||||
#define NORMAL_FLAG 0x00
|
||||
#define MOVING_FLAG_SET 0xAA
|
||||
#define MOVING_FLAG_CLEAR 0x00
|
||||
|
||||
const char *ssid = "IOT-pecan";
|
||||
const char *password = "aaaaaaaa";
|
||||
const char *mqttServer = "192.168.1.110";
|
||||
const int mqttPort = 1883;
|
||||
const char *mqttHeightTopic = "/jc/height";
|
||||
const char *mqttAngleTopic = "/jc/angle";
|
||||
const char *mqttStopTopic = "/jc/stop";
|
||||
const char *mqttHomingFlagTopic = "/jc/homing_mode";
|
||||
const char *mqttDebugTopic = "/jc/debug";
|
||||
const char *mqttStatusTopic = "/jc/status";
|
||||
|
||||
const char *mqttHeightLogTopic = "/jc/height/log";
|
||||
const char *mqttAngleLogTopic = "/jc/angle/log";
|
||||
const char *mqttRPMLogTopic = "/jc/rpm/log";
|
||||
|
||||
const int steps_per_thou = 22;
|
||||
|
||||
FastAccelStepperEngine engine = FastAccelStepperEngine();
|
||||
FastAccelStepper *bottom_stepper = nullptr;
|
||||
FastAccelStepper *top_stepper = nullptr;
|
||||
|
||||
RotaryEncoder encoder(encoder_a, encoder_b);
|
||||
|
||||
WiFiClient wifiClient;
|
||||
PubSubClient mqttClient(wifiClient);
|
||||
|
||||
volatile long bottom_step_goal = 0, top_step_goal = 0;
|
||||
volatile bool bottom_step_done = true, top_step_done = true;
|
||||
volatile bool bottom_step_sent = false, top_step_sent = false;
|
||||
volatile bool stop = false;
|
||||
bool system_locked = false;
|
||||
|
||||
void writePositionToEEPROM(int addr, long pos)
|
||||
{
|
||||
EEPROM.write(addr, (pos >> 24) & 0xFF);
|
||||
EEPROM.write(addr + 1, (pos >> 16) & 0xFF);
|
||||
EEPROM.write(addr + 2, (pos >> 8) & 0xFF);
|
||||
EEPROM.write(addr + 3, pos & 0xFF);
|
||||
}
|
||||
|
||||
long readPositionFromEEPROM(int addr)
|
||||
{
|
||||
long pos = ((long)EEPROM.read(addr) << 24) |
|
||||
((long)EEPROM.read(addr + 1) << 16) |
|
||||
((long)EEPROM.read(addr + 2) << 8) |
|
||||
(long)EEPROM.read(addr + 3);
|
||||
return pos;
|
||||
}
|
||||
|
||||
volatile long top_angle_difference_steps = readPositionFromEEPROM(EEPROM_TOP_BOTTOM_DIFF_ADDR);
|
||||
|
||||
void callback(char *topic, byte *payload, unsigned int length)
|
||||
{
|
||||
String topic_str = String(topic);
|
||||
String payload_str = "";
|
||||
for (unsigned int i = 0; i < length; i++)
|
||||
payload_str += (char)payload[i];
|
||||
int value = payload_str.toInt();
|
||||
|
||||
if (topic_str == mqttHeightTopic && !system_locked)
|
||||
{
|
||||
value -= 1875 - 210;
|
||||
value *= steps_per_thou;
|
||||
stop = false;
|
||||
bottom_step_goal = value;
|
||||
bottom_step_done = false;
|
||||
bottom_step_sent = false;
|
||||
top_step_goal = value + top_angle_difference_steps;
|
||||
top_step_done = false;
|
||||
top_step_sent = false;
|
||||
}
|
||||
else if (topic_str == mqttAngleTopic && !system_locked)
|
||||
{
|
||||
stop = false;
|
||||
top_angle_difference_steps = value * steps_per_thou;
|
||||
top_step_goal = bottom_step_goal + top_angle_difference_steps;
|
||||
top_step_done = false;
|
||||
top_step_sent = false;
|
||||
}
|
||||
else if (topic_str == mqttStopTopic && !system_locked)
|
||||
{
|
||||
stop = true;
|
||||
}
|
||||
else if (topic_str == mqttHomingFlagTopic)
|
||||
{
|
||||
if (payload_str != "0")
|
||||
{
|
||||
EEPROM.write(EEPROM_FLAG_ADDR, HOMING_FLAG);
|
||||
mqttClient.publish(mqttDebugTopic, "Startup flag set to HOMING");
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(EEPROM_FLAG_ADDR, NORMAL_FLAG);
|
||||
mqttClient.publish(mqttDebugTopic, "Startup flag set to NORMAL");
|
||||
}
|
||||
EEPROM.commit();
|
||||
}
|
||||
|
||||
if (top_step_goal < -1665 * steps_per_thou)
|
||||
top_step_goal = -1665 * steps_per_thou;
|
||||
if (bottom_step_goal < -1665 * steps_per_thou)
|
||||
bottom_step_goal = -1665 * steps_per_thou;
|
||||
if (top_step_goal > 0)
|
||||
top_step_goal = 0;
|
||||
if (bottom_step_goal > 0)
|
||||
bottom_step_goal = 0;
|
||||
}
|
||||
|
||||
void reconnect()
|
||||
{
|
||||
while (!mqttClient.connected())
|
||||
{
|
||||
if (WiFi.status() != WL_CONNECTED)
|
||||
WiFi.reconnect();
|
||||
Serial.println("Attempting MQTT connection...");
|
||||
if (mqttClient.connect("ESP32Client"))
|
||||
{
|
||||
Serial.println("connected");
|
||||
mqttClient.subscribe(mqttHeightTopic);
|
||||
mqttClient.subscribe(mqttAngleTopic);
|
||||
mqttClient.subscribe(mqttStopTopic);
|
||||
mqttClient.subscribe(mqttHomingFlagTopic);
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("failed, rc=");
|
||||
Serial.print(mqttClient.state());
|
||||
Serial.println(" try again in 5 seconds");
|
||||
delay(5000);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
long last_publish_time = 0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
EEPROM.begin(EEPROM_SIZE);
|
||||
engine.init();
|
||||
|
||||
WiFi.begin(ssid, password);
|
||||
while (WiFi.status() != WL_CONNECTED)
|
||||
{
|
||||
delay(1000);
|
||||
Serial.println("Connecting to WiFi...");
|
||||
}
|
||||
Serial.println("Connected to WiFi");
|
||||
|
||||
mqttClient.setServer(mqttServer, mqttPort);
|
||||
mqttClient.setCallback(callback);
|
||||
|
||||
uint8_t startupFlag = EEPROM.read(EEPROM_FLAG_ADDR);
|
||||
Serial.print("Startup flag: ");
|
||||
Serial.println(startupFlag);
|
||||
|
||||
uint8_t bottomMovingFlag = EEPROM.read(EEPROM_BOTTOM_MOVING_FLAG_ADDR);
|
||||
uint8_t topMovingFlag = EEPROM.read(EEPROM_TOP_MOVING_FLAG_ADDR);
|
||||
if (startupFlag != HOMING_FLAG && (bottomMovingFlag != MOVING_FLAG_CLEAR || topMovingFlag != MOVING_FLAG_CLEAR))
|
||||
{
|
||||
system_locked = true;
|
||||
mqttClient.publish(mqttDebugTopic, "FAULT: NEEDS HOMING RESET");
|
||||
Serial.println("System locked: Improper shutdown detected. Awaiting homing reset.");
|
||||
EEPROM.write(EEPROM_FLAG_ADDR, HOMING_FLAG);
|
||||
EEPROM.commit();
|
||||
}
|
||||
|
||||
bottom_stepper = engine.stepperConnectToPin(bottom_step_pin);
|
||||
if (bottom_stepper)
|
||||
{
|
||||
bottom_stepper->setDirectionPin(bottom_dir_pin);
|
||||
bottom_stepper->setEnablePin(bottom_en_pin, false);
|
||||
bottom_stepper->setSpeedInHz(1000);
|
||||
bottom_stepper->setAcceleration(250);
|
||||
if (startupFlag == HOMING_FLAG)
|
||||
{
|
||||
Serial.println("Starting in homing mode (bottom)");
|
||||
bottom_stepper->setCurrentPosition(0);
|
||||
writePositionToEEPROM(EEPROM_BOTTOM_POS_ADDR, bottom_stepper->getCurrentPosition());
|
||||
EEPROM.write(EEPROM_FLAG_ADDR, NORMAL_FLAG);
|
||||
EEPROM.write(EEPROM_BOTTOM_MOVING_FLAG_ADDR, MOVING_FLAG_CLEAR);
|
||||
EEPROM.commit();
|
||||
mqttClient.publish(mqttDebugTopic, "Started in HOMING mode, flag cleared");
|
||||
}
|
||||
else
|
||||
{
|
||||
bottom_stepper->setCurrentPosition(readPositionFromEEPROM(EEPROM_BOTTOM_POS_ADDR));
|
||||
mqttClient.publish(mqttDebugTopic, "Started in NORMAL mode");
|
||||
mqttClient.publish(mqttDebugTopic, "Bottom stepper loaded %d position from EEPROM", bottom_stepper->getCurrentPosition());
|
||||
}
|
||||
}
|
||||
|
||||
top_stepper = engine.stepperConnectToPin(top_step_pin);
|
||||
if (top_stepper)
|
||||
{
|
||||
top_stepper->setDirectionPin(top_dir_pin);
|
||||
top_stepper->setEnablePin(top_en_pin, false);
|
||||
top_stepper->setSpeedInHz(1000);
|
||||
top_stepper->setAcceleration(250);
|
||||
if (startupFlag == HOMING_FLAG)
|
||||
{
|
||||
Serial.println("Starting in homing mode (top)");
|
||||
top_stepper->setCurrentPosition(0);
|
||||
writePositionToEEPROM(EEPROM_TOP_POS_ADDR, top_stepper->getCurrentPosition());
|
||||
EEPROM.write(EEPROM_TOP_MOVING_FLAG_ADDR, MOVING_FLAG_CLEAR);
|
||||
EEPROM.commit();
|
||||
}
|
||||
else
|
||||
{
|
||||
top_stepper->setCurrentPosition(readPositionFromEEPROM(EEPROM_TOP_POS_ADDR));
|
||||
mqttClient.publish(mqttDebugTopic, "Top stepper loaded %d position from EEPROM", top_stepper->getCurrentPosition());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (!mqttClient.connected())
|
||||
reconnect();
|
||||
mqttClient.loop();
|
||||
|
||||
encoder.tick();
|
||||
|
||||
if (millis() - last_publish_time > 1000)
|
||||
{
|
||||
last_publish_time = millis();
|
||||
mqttClient.publish(mqttHeightLogTopic, String(1665 + bottom_stepper->getCurrentPosition() / steps_per_thou).c_str());
|
||||
mqttClient.publish(mqttAngleLogTopic, String((top_stepper->getCurrentPosition() - bottom_stepper->getCurrentPosition()) / steps_per_thou).c_str());
|
||||
mqttClient.publish(mqttRPMLogTopic, String(encoder.getRPM()).c_str());
|
||||
}
|
||||
|
||||
if (system_locked)
|
||||
{
|
||||
bottom_stepper->disableOutputs();
|
||||
top_stepper->disableOutputs();
|
||||
return;
|
||||
}
|
||||
|
||||
if (stop)
|
||||
{
|
||||
bottom_stepper->disableOutputs();
|
||||
top_stepper->disableOutputs();
|
||||
}
|
||||
else
|
||||
{
|
||||
bottom_stepper->enableOutputs();
|
||||
top_stepper->enableOutputs();
|
||||
}
|
||||
|
||||
if (bottom_stepper->getCurrentPosition() != bottom_step_goal && !bottom_step_done && !bottom_step_sent)
|
||||
{
|
||||
bottom_stepper->moveTo(bottom_step_goal);
|
||||
bottom_step_sent = true;
|
||||
EEPROM.write(EEPROM_BOTTOM_MOVING_FLAG_ADDR, MOVING_FLAG_SET);
|
||||
EEPROM.commit();
|
||||
Serial.println("Moving bottom stepper");
|
||||
}
|
||||
|
||||
if (top_stepper->getCurrentPosition() != top_step_goal && !top_step_done && !top_step_sent)
|
||||
{
|
||||
top_stepper->moveTo(top_step_goal);
|
||||
top_step_sent = true;
|
||||
EEPROM.write(EEPROM_TOP_MOVING_FLAG_ADDR, MOVING_FLAG_SET);
|
||||
EEPROM.commit();
|
||||
Serial.println("Moving top stepper");
|
||||
}
|
||||
|
||||
if (bottom_stepper->getCurrentPosition() == bottom_step_goal && !bottom_step_done && bottom_step_sent)
|
||||
{
|
||||
bottom_step_done = true;
|
||||
bottom_step_sent = false;
|
||||
writePositionToEEPROM(EEPROM_BOTTOM_POS_ADDR, bottom_stepper->getCurrentPosition());
|
||||
writePositionToEEPROM(EEPROM_TOP_BOTTOM_DIFF_ADDR, top_angle_difference_steps);
|
||||
EEPROM.write(EEPROM_BOTTOM_MOVING_FLAG_ADDR, MOVING_FLAG_CLEAR);
|
||||
EEPROM.commit();
|
||||
Serial.println("Bottom stepper done");
|
||||
}
|
||||
|
||||
if (top_stepper->getCurrentPosition() == top_step_goal && !top_step_done && top_step_sent)
|
||||
{
|
||||
top_step_done = true;
|
||||
top_step_sent = false;
|
||||
writePositionToEEPROM(EEPROM_TOP_POS_ADDR, top_stepper->getCurrentPosition());
|
||||
writePositionToEEPROM(EEPROM_TOP_BOTTOM_DIFF_ADDR, top_angle_difference_steps);
|
||||
EEPROM.write(EEPROM_TOP_MOVING_FLAG_ADDR, MOVING_FLAG_CLEAR);
|
||||
EEPROM.commit();
|
||||
Serial.println("Top stepper done");
|
||||
}
|
||||
}
|
|
@ -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
|
Loading…
Reference in New Issue