Cleanup and fixes
This commit is contained in:
parent
4900c36e0b
commit
5e56ede55c
|
@ -0,0 +1,15 @@
|
||||||
|
!! On Swimtracker board the JTAG pins are not labeled correctly !
|
||||||
|
one pin even needs to be soldered manually
|
||||||
|
|
||||||
|
|
||||||
|
------|------|-----------------
|
||||||
|
GND | | schwarz
|
||||||
|
3.3V | | rot
|
||||||
|
IO13 | TCK | weiss
|
||||||
|
IO14 | TMS | grau
|
||||||
|
IO12 | TDI | lila
|
||||||
|
IO15 | TDO | blau
|
||||||
|
EN | | grun
|
||||||
|
IO0 | | braun
|
||||||
|
RXD | | orange
|
||||||
|
TXD | | gelb
|
|
@ -14,10 +14,6 @@ void Logger::init()
|
||||||
{
|
{
|
||||||
theLogger = new Logger();
|
theLogger = new Logger();
|
||||||
#ifdef PLATFORM_ESP32
|
#ifdef PLATFORM_ESP32
|
||||||
Serial.begin(115200);
|
|
||||||
while (!Serial)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -18,10 +18,12 @@
|
||||||
Logger::getInstance()->log(__VA_ARGS__); \
|
Logger::getInstance()->log(__VA_ARGS__); \
|
||||||
}
|
}
|
||||||
|
|
||||||
#define LOG_TRACE(...) \
|
/*#define LOG_TRACE(...) \
|
||||||
{ \
|
{ \
|
||||||
Logger::getInstance()->log(__VA_ARGS__); \
|
Logger::getInstance()->log(__VA_ARGS__); \
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
#define LOG_TRACE(...) {}
|
||||||
|
|
||||||
#define LOG_WARNING(...) \
|
#define LOG_WARNING(...) \
|
||||||
{ \
|
{ \
|
||||||
|
@ -55,8 +57,7 @@ public:
|
||||||
std::forward<Args>(args)...);
|
std::forward<Args>(args)...);
|
||||||
#pragma GCC diagnostic pop
|
#pragma GCC diagnostic pop
|
||||||
|
|
||||||
|
Serial.println(&data_[currentSize_]);
|
||||||
//Serial.println(&data_[currentSize_]);
|
|
||||||
if(charsWritten > 0)
|
if(charsWritten > 0)
|
||||||
{
|
{
|
||||||
currentSize_ += charsWritten + 1; // + 1 for trailing zero
|
currentSize_ += charsWritten + 1; // + 1 for trailing zero
|
||||||
|
|
|
@ -8,7 +8,7 @@ public:
|
||||||
bool measure(uint16_t &measurementOut)
|
bool measure(uint16_t &measurementOut)
|
||||||
{
|
{
|
||||||
long value = hx711_.read_average(CONFIG_MEASUREMENT_AVG_COUNT);
|
long value = hx711_.read_average(CONFIG_MEASUREMENT_AVG_COUNT);
|
||||||
LOG_TRACE("rv %ld\n", value);
|
LOG_TRACE("rv %ld", value);
|
||||||
value -= offset_;
|
value -= offset_;
|
||||||
|
|
||||||
if (value < 0)
|
if (value < 0)
|
||||||
|
@ -28,7 +28,7 @@ public:
|
||||||
{
|
{
|
||||||
auto v1 = hx711_.read_average(3);
|
auto v1 = hx711_.read_average(3);
|
||||||
offset_ = hx711_.read_average(numMeasurementsToAverage);
|
offset_ = hx711_.read_average(numMeasurementsToAverage);
|
||||||
LOG_INFO("Init reading %ld, Tare offset %ld\n", v1, offset_);
|
LOG_INFO("Init reading %ld, Tare offset %ld", v1, offset_);
|
||||||
}
|
}
|
||||||
|
|
||||||
const long &offset() const { return offset_; }
|
const long &offset() const { return offset_; }
|
||||||
|
|
|
@ -105,6 +105,7 @@ private:
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
LOG_INFO("Creating new session file");
|
||||||
auto file = portablefs::open(filename.c_str(), "w");
|
auto file = portablefs::open(filename.c_str(), "w");
|
||||||
StreamingMsgPackEncoder<portablefs::File> encoder(&file);
|
StreamingMsgPackEncoder<portablefs::File> encoder(&file);
|
||||||
chunk->serialize(encoder);
|
chunk->serialize(encoder);
|
||||||
|
|
|
@ -24,9 +24,12 @@ board_upload.flash_size = "16MB"
|
||||||
#build_flags = -Wl,-Teagle.flash.2m1m.ld
|
#build_flags = -Wl,-Teagle.flash.2m1m.ld
|
||||||
build_flags = -DPLATFORM_ESP32 -DBOARD_HAS_PSRAM -mfix-esp32-psram-cache-issue
|
build_flags = -DPLATFORM_ESP32 -DBOARD_HAS_PSRAM -mfix-esp32-psram-cache-issue
|
||||||
framework = arduino
|
framework = arduino
|
||||||
monitor_port = /dev/ttyUSB0
|
monitor_port = /dev/ttyUSB1
|
||||||
upload_port = /dev/ttyUSB0
|
upload_port = /dev/ttyUSB1
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
debug_tool = esp-prog
|
||||||
|
#upload_protocol = esp-prog
|
||||||
|
debug_init_break = tbreak setup
|
||||||
lib_deps =
|
lib_deps =
|
||||||
NTPClient
|
NTPClient
|
||||||
HX711@0.7.4
|
HX711@0.7.4
|
||||||
|
|
|
@ -36,14 +36,13 @@ class LoggingAPI
|
||||||
if(running_)
|
if(running_)
|
||||||
{
|
{
|
||||||
const Logger * logger = Logger::getInstance();
|
const Logger * logger = Logger::getInstance();
|
||||||
const auto beginIt = lastEnd_;
|
|
||||||
const auto endIt = logger->end();
|
|
||||||
|
|
||||||
StaticJsonDocument<512> data;
|
const auto endIt = logger->end();
|
||||||
for(auto it = beginIt; it != endIt; ++it) {
|
StaticJsonDocument<1024> data;
|
||||||
|
for(auto it = lastEnd_; it != endIt; ++it) {
|
||||||
data["time"] = it.time_millis();
|
data["time"] = it.time_millis();
|
||||||
data["msg"] = it.message();
|
data["msg"] = it.message();
|
||||||
server.template sendToAll<512>(MessageCode::LOG_UPDATE, data);
|
server.template sendToAll<1024>(MessageCode::LOG_UPDATE, data);
|
||||||
}
|
}
|
||||||
lastEnd_ = endIt;
|
lastEnd_ = endIt;
|
||||||
}
|
}
|
||||||
|
@ -52,6 +51,6 @@ class LoggingAPI
|
||||||
private:
|
private:
|
||||||
bool running_ = false;
|
bool running_ = false;
|
||||||
Logger::iterator lastEnd_ = Logger::iterator(nullptr);
|
Logger::iterator lastEnd_ = Logger::iterator(nullptr);
|
||||||
bool firstCall_ = false;
|
bool firstCall_ = true;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -50,15 +50,19 @@ public:
|
||||||
|
|
||||||
if (server_.poll())
|
if (server_.poll())
|
||||||
{
|
{
|
||||||
LOG_INFO("new websocket connection, storing at pos %d - occupancy: ", nextFreeClient_);
|
|
||||||
clients_[nextFreeClient_] = server_.accept();
|
clients_[nextFreeClient_] = server_.accept();
|
||||||
clients_[nextFreeClient_].onMessage(onMessage);
|
clients_[nextFreeClient_].onMessage(onMessage);
|
||||||
this->onClientConnectImpl(clients_[nextFreeClient_]);
|
this->onClientConnectImpl(clients_[nextFreeClient_]);
|
||||||
nextFreeClient_ = (nextFreeClient_ + 1) % MAX_WEBSOCKET_CONNECTIONS;
|
nextFreeClient_ = (nextFreeClient_ + 1) % MAX_WEBSOCKET_CONNECTIONS;
|
||||||
|
|
||||||
|
if(MAX_WEBSOCKET_CONNECTIONS == 3) {
|
||||||
|
LOG_INFO("new websocket connection, storing at pos %d - occupancy: %d%d%d", nextFreeClient_, clients_[0].available(), clients_[1].available(), clients_[2].available());
|
||||||
|
} else {
|
||||||
|
LOG_INFO("new websocket connection, storing at pos %d - occupancy:", nextFreeClient_);
|
||||||
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
||||||
LOG_INFO((clients_[i].available()) ? "x" : "o");
|
LOG_INFO((clients_[i].available()) ? "x" : "o");
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
||||||
clients_[i].poll();
|
clients_[i].poll();
|
||||||
|
@ -69,12 +73,13 @@ public:
|
||||||
template <size_t bufferSize>
|
template <size_t bufferSize>
|
||||||
void sendToAll(MessageCode msgCode, const JsonDocument &content)
|
void sendToAll(MessageCode msgCode, const JsonDocument &content)
|
||||||
{
|
{
|
||||||
|
static_assert(sizeof(MessageCode) == 1);
|
||||||
char buffer[bufferSize];
|
char buffer[bufferSize];
|
||||||
buffer[0] = (char)(msgCode);
|
buffer[0] = (char)(msgCode);
|
||||||
size_t bytesWritten = serializeMsgPack(content, buffer + sizeof(msgCode), bufferSize - sizeof(msgCode));
|
size_t bytesWritten = serializeMsgPack(content, buffer + sizeof(msgCode), bufferSize - sizeof(msgCode));
|
||||||
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
for (int i = 0; i < MAX_WEBSOCKET_CONNECTIONS; ++i)
|
||||||
if (clients_[i].available())
|
if (clients_[i].available())
|
||||||
clients_[i].sendBinary(buffer, bytesWritten);
|
clients_[i].sendBinary(buffer, bytesWritten + sizeof(msgCode));
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendToAll(MessageCode msgCode, const JsonDocument &content)
|
void sendToAll(MessageCode msgCode, const JsonDocument &content)
|
||||||
|
|
|
@ -433,6 +433,10 @@ void mdnsSetup(const String &fullHostname)
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
while (!Serial)
|
||||||
|
{
|
||||||
|
}
|
||||||
// Serial
|
// Serial
|
||||||
Logger::init();
|
Logger::init();
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,5 @@
|
||||||
|
.pio
|
||||||
|
.vscode/.browse.c_cpp.db*
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
.vscode/launch.json
|
||||||
|
.vscode/ipch
|
|
@ -0,0 +1,12 @@
|
||||||
|
[platformio]
|
||||||
|
default_envs = esp
|
||||||
|
|
||||||
|
[env:esp]
|
||||||
|
platform = espressif8266
|
||||||
|
board = nodemcuv2
|
||||||
|
framework = arduino
|
||||||
|
monitor_port = /dev/ttyUSB0
|
||||||
|
upload_port = /dev/ttyUSB0
|
||||||
|
monitor_speed = 115200
|
||||||
|
lib_deps =
|
||||||
|
ArduinoJson
|
|
@ -0,0 +1,76 @@
|
||||||
|
#include "MotorControl.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
constexpr int PORT_FORWARD = 4;
|
||||||
|
constexpr int PORT_BACKWARD = 16;
|
||||||
|
constexpr int PORT_SPEED = 5;
|
||||||
|
|
||||||
|
// PWM settings
|
||||||
|
constexpr int PWM_FREQ = 20000;
|
||||||
|
constexpr int PWM_CHANNEL = 0;
|
||||||
|
constexpr int PWM_RESOLUTION = 255;
|
||||||
|
|
||||||
|
void MotorControl::begin()
|
||||||
|
{
|
||||||
|
pinMode(PORT_SPEED, OUTPUT);
|
||||||
|
pinMode(PORT_FORWARD, OUTPUT);
|
||||||
|
pinMode(PORT_BACKWARD, OUTPUT);
|
||||||
|
|
||||||
|
analogWriteRange(PWM_RESOLUTION);
|
||||||
|
analogWriteFreq(PWM_FREQ);
|
||||||
|
startTime_ = millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorControl::addCmd(float signedSpeed, unsigned long duration)
|
||||||
|
{
|
||||||
|
if (numCmds_ < MAX_MOTOR_COMMANDS)
|
||||||
|
motorCommands_[numCmds_++] = {int(signedSpeed * PWM_RESOLUTION), duration};
|
||||||
|
else
|
||||||
|
Serial.println("Too many commands");
|
||||||
|
}
|
||||||
|
|
||||||
|
float MotorControl::speed(int cmdIdx) const
|
||||||
|
{
|
||||||
|
return float(motorCommands_[cmdIdx].directionAndSpeed) / float(PWM_RESOLUTION);
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long MotorControl::duration(int cmdIdx) const
|
||||||
|
{
|
||||||
|
return motorCommands_[cmdIdx].delayToNextCmdInMs;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotorControl::iteration()
|
||||||
|
{
|
||||||
|
if (numCmds_ == 0)
|
||||||
|
{
|
||||||
|
analogWrite(PORT_SPEED, 0);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long timeElapsed = millis() - startTime_;
|
||||||
|
while (timeElapsed > motorCommands_[currentCmd_].delayToNextCmdInMs)
|
||||||
|
{
|
||||||
|
const auto curCmdDuration = motorCommands_[currentCmd_].delayToNextCmdInMs;
|
||||||
|
timeElapsed -= curCmdDuration;
|
||||||
|
startTime_ += curCmdDuration;
|
||||||
|
currentCmd_ = (currentCmd_ + 1) % numCmds_;
|
||||||
|
}
|
||||||
|
|
||||||
|
const auto &curCmd = motorCommands_[currentCmd_];
|
||||||
|
const auto &nextCmd = motorCommands_[(currentCmd_ + 1) % numCmds_];
|
||||||
|
const float fraction = float(timeElapsed) / float(curCmd.delayToNextCmdInMs);
|
||||||
|
const int interpolated = int((1.f - fraction) * curCmd.directionAndSpeed + fraction * nextCmd.directionAndSpeed);
|
||||||
|
|
||||||
|
if (interpolated < 0)
|
||||||
|
{
|
||||||
|
analogWrite(PORT_SPEED, -interpolated);
|
||||||
|
digitalWrite(PORT_FORWARD, 0);
|
||||||
|
digitalWrite(PORT_BACKWARD, 1);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
analogWrite(PORT_SPEED, interpolated);
|
||||||
|
digitalWrite(PORT_FORWARD, 1);
|
||||||
|
digitalWrite(PORT_BACKWARD, 0);
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,31 @@
|
||||||
|
|
||||||
|
|
||||||
|
class MotorControl
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
void begin();
|
||||||
|
void clear()
|
||||||
|
{
|
||||||
|
numCmds_ = 0;
|
||||||
|
currentCmd_ = 0;
|
||||||
|
}
|
||||||
|
void addCmd(float signedSpeed, unsigned long duration);
|
||||||
|
void iteration();
|
||||||
|
|
||||||
|
int numCommands() const { return numCmds_; }
|
||||||
|
float speed(int cmdIdx) const;
|
||||||
|
unsigned long duration(int cmdIdx) const;
|
||||||
|
|
||||||
|
private:
|
||||||
|
static constexpr int MAX_MOTOR_COMMANDS = 1024;
|
||||||
|
struct MotorCmd
|
||||||
|
{
|
||||||
|
int directionAndSpeed; // fraction of PWM_RESO
|
||||||
|
unsigned long delayToNextCmdInMs;
|
||||||
|
};
|
||||||
|
|
||||||
|
int currentCmd_ = 0;
|
||||||
|
int numCmds_ = 0;
|
||||||
|
MotorCmd motorCommands_[MAX_MOTOR_COMMANDS];
|
||||||
|
unsigned long startTime_ = 0;
|
||||||
|
};
|
|
@ -0,0 +1,87 @@
|
||||||
|
#include "MotorControl.h"
|
||||||
|
|
||||||
|
#include <ESP8266WiFi.h>
|
||||||
|
#include <ESP8266WebServer.h>
|
||||||
|
#include <ArduinoJson.h>
|
||||||
|
|
||||||
|
ESP8266WebServer server(80);
|
||||||
|
MotorControl motorCtl;
|
||||||
|
const char *webBuffer[1024 * 4];
|
||||||
|
|
||||||
|
void wifiSetup()
|
||||||
|
{
|
||||||
|
static const char *ssid = "WLAN";
|
||||||
|
static const char *password = "Bau3rWLAN";
|
||||||
|
|
||||||
|
WiFi.begin(ssid, password);
|
||||||
|
WiFi.hostname("swimtracker-tester");
|
||||||
|
|
||||||
|
while (WiFi.status() != WL_CONNECTED)
|
||||||
|
{
|
||||||
|
delay(500);
|
||||||
|
Serial.println("Waiting to connect...");
|
||||||
|
}
|
||||||
|
Serial.print("IP address: ");
|
||||||
|
Serial.println(WiFi.localIP());
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleGetRoot()
|
||||||
|
{
|
||||||
|
DynamicJsonDocument doc(motorCtl.numCommands() * 16 + 128);
|
||||||
|
JsonArray speeds = doc.createNestedArray("speeds");
|
||||||
|
JsonArray durations = doc.createNestedArray("durations");
|
||||||
|
for (int i = 0; i < motorCtl.numCommands(); ++i)
|
||||||
|
{
|
||||||
|
speeds.add(motorCtl.speed(i));
|
||||||
|
durations.add(motorCtl.duration(i));
|
||||||
|
}
|
||||||
|
size_t length = serializeJson(doc, webBuffer, sizeof(webBuffer));
|
||||||
|
server.send(200, "application/json", (const char *)webBuffer, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handlePostRoot()
|
||||||
|
{
|
||||||
|
String postBody = server.arg("plain");
|
||||||
|
DynamicJsonDocument doc(postBody.length() * 2 + 256);
|
||||||
|
DeserializationError error = deserializeJson(doc, postBody);
|
||||||
|
if (error || !doc.containsKey("speeds") || !doc.containsKey("durations"))
|
||||||
|
server.send(400, "application/json", "{ \"msg\" : \"Parsing error\" }");
|
||||||
|
else
|
||||||
|
{
|
||||||
|
JsonArray speeds = doc["speeds"].as<JsonArray>();
|
||||||
|
JsonArray durations = doc["durations"].as<JsonArray>();
|
||||||
|
if (speeds.size() != durations.size())
|
||||||
|
server.send(400, "application/json", "{ \"msg\" : \"Arrays have to have same length!\" }");
|
||||||
|
else
|
||||||
|
{
|
||||||
|
motorCtl.clear();
|
||||||
|
auto speedIt = speeds.begin();
|
||||||
|
auto durationIt = durations.begin();
|
||||||
|
for (; speedIt != speeds.end() && durationIt != durations.end(); ++durationIt, ++speedIt)
|
||||||
|
{
|
||||||
|
motorCtl.addCmd(speedIt->as<float>(), durationIt->as<unsigned long>());
|
||||||
|
}
|
||||||
|
server.send(200, "application/json", "{ \"msg\" : \"Ok\" }");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
wifiSetup();
|
||||||
|
|
||||||
|
server.on("/", HTTP_GET, handleGetRoot);
|
||||||
|
server.on("/", HTTP_POST, handlePostRoot);
|
||||||
|
|
||||||
|
server.begin(); //Start the server
|
||||||
|
Serial.println("Server listening");
|
||||||
|
|
||||||
|
motorCtl.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
server.handleClient(); //Handling of incoming client requests
|
||||||
|
motorCtl.iteration();
|
||||||
|
}
|
Loading…
Reference in New Issue