This commit is contained in:
2023-11-12 13:20:26 +01:00
parent eebb355f59
commit 4abd103830
7 changed files with 90 additions and 53 deletions

View File

@@ -23,3 +23,5 @@ build_flags =
-DCORE_DEBUG_LEVEL=3 -DCORE_DEBUG_LEVEL=3
-DNDEF_DEBUG=1 -DNDEF_DEBUG=1
upload_protocol = esptool upload_protocol = esptool
;upload_protocol = espota
;upload_port = miniskidi.local

View File

@@ -27,9 +27,9 @@ void setupmotors()
delay(50); delay(50);
} }
bucketServo.attach(bucketServoPin); bucketServo.attach(bucketServoPin);
bucketServo.write(default_bucketTilt);
//auxServo.attach(auxServoPin); //auxServo.attach(auxServoPin);
//auxControl(default_auxControl); //auxControl(default_auxControl);
bucketServo.write(default_bucketTilt);
} }
void drivemotor(uint8_t num, int dirspeed) void drivemotor(uint8_t num, int dirspeed)
@@ -40,12 +40,13 @@ void drivemotor(uint8_t num, int dirspeed)
{ {
motors[num].stop(); motors[num].stop();
log_v("stop"); log_v("stop");
return;
} }
else else
{ {
//uint8_t speed = map(dirspeed, -330, 330, -100, 100);
log_i("drive motor %u, speed %d", num, dirspeed); log_i("drive motor %u, speed %d", num, dirspeed);
uint8_t speed = map(dirspeed, -255, 255, -100, 100); motors[num].move(dirspeed);
motors[num].move(speed);
motors[num].prevsetpoint = dirspeed; motors[num].prevsetpoint = dirspeed;
} }
} }
@@ -54,43 +55,50 @@ void drivemotor(uint8_t num, int dirspeed)
log_e("invalid motor num %d", num); log_e("invalid motor num %d", num);
} }
} }
int prevBucketAngle = 0; int prevBucketAngle = 0;
uint32_t lastbuckettimer = 0; uint32_t lastbuckettimer = 0;
void bucketTilt(int bucketServoValue) void bucketTilt(int bucketServoValue)
{ {
if(millis()- lastbuckettimer > BUCKETTIMER) if(millis()- lastbuckettimer > BUCKETTIMER)
{ {
log_i("bucket command received = %i", bucketServoValue);
int servo = 0; int servo = 0;
if(bucketServoValue == 0) if(bucketServoValue == 0)
{ {
log_v("bucket stop");
return; return;
} }
else if(bucketServoValue > 0) else if(bucketServoValue > 0)
{ {
servo = prevBucketAngle + SERVOSTEP; servo = prevBucketAngle + SERVOSTEP;
log_i("bucket UP (%d)", servo);
} }
else else
{ {
servo = prevBucketAngle - SERVOSTEP; servo = prevBucketAngle - SERVOSTEP;
log_i("bucket DOWN (%d)", servo);
} }
if(servo > SERVOMAX) servo = SERVOMAX; if(servo > SERVOMAX) servo = SERVOMAX;
if(servo < SERVOMIN) servo = SERVOMIN; if(servo < SERVOMIN) servo = SERVOMIN;
bucketServo.write(servo); bucketServo.write(servo);
log_i("bucket (%i) angle=(%d)", bucketServoValue, servo);
lastbuckettimer = millis(); lastbuckettimer = millis();
prevBucketAngle = servo;
} }
} }
void AbsBucketTilt(int bucketServoValue) void AbsBucketTilt(int bucketServoValue)
{ {
log_i("drive bucket servo, angle %d", bucketServoValue);
delay(5);
bucketServo.write(bucketServoValue); bucketServo.write(bucketServoValue);
} }
void auxControl(int auxServoValue) void auxControl(int auxServoValue)
{ {
log_i("drive aux servo, angle %d", auxServoValue);
delay(5);
auxServo.write(auxServoValue); auxServo.write(auxServoValue);
} }

View File

@@ -6,25 +6,27 @@
#include "webserver.h" #include "webserver.h"
#include "ota.h" #include "ota.h"
const char* ssid = "iot"; const char* ssid = "iot";
const char* pwd = "Rijnstraat214"; const char* pwd = "Rijnstraat214";
void setup(void) void setup(void)
{ {
log_i("init hardware");
setupmotors();
Serial.begin(115200); Serial.begin(115200);
delay(1000);
log_i("init hardware");
WiFi.mode(WIFI_STA); WiFi.mode(WIFI_STA);
WiFi.begin(ssid,pwd ); WiFi.begin(ssid,pwd );
if (WiFi.waitForConnectResult() != WL_CONNECTED) if (WiFi.waitForConnectResult() != WL_CONNECTED)
{ {
Serial.printf("WiFi Failed!\n"); log_e("WiFi Failed! rebooting in 2sec");
return; delay(2000);
ESP.restart();
} }
IPAddress IP = WiFi.localIP(); log_i("IP address: %s", WiFi.localIP().toString());
Serial.print("AP IP address: ");
Serial.println(IP);
initOTA("MiniSkidi"); initOTA("MiniSkidi");
setupmotors();
setup_webserver(); setup_webserver();
} }

View File

@@ -14,11 +14,11 @@
#define ARM_MOTOR 2 #define ARM_MOTOR 2
#define SERVOSTEP 5 #define SERVOSTEP 10
#define SERVOMIN 0 #define SERVOMIN 50
#define SERVOMAX 180 #define SERVOMAX 180
#define BUCKETTIMER 100 #define BUCKETTIMER 10
struct MOTOR_PINS struct MOTOR_PINS
{ {

View File

@@ -3,10 +3,8 @@
void initOTA(const char* hostname) void initOTA(const char* hostname)
{ {
Serial.begin(115200);
Serial.println("Booting");
while (WiFi.waitForConnectResult() != WL_CONNECTED) { while (WiFi.waitForConnectResult() != WL_CONNECTED) {
Serial.println("Connection Failed! Rebooting..."); log_e("Connection Failed! Rebooting...");
delay(5000); delay(5000);
ESP.restart(); ESP.restart();
} }
@@ -17,13 +15,7 @@ void initOTA(const char* hostname)
// Hostname defaults to esp3232-[MAC] // Hostname defaults to esp3232-[MAC]
ArduinoOTA.setHostname(hostname); ArduinoOTA.setHostname(hostname);
// No authentication by default
// ArduinoOTA.setPassword("admin");
// Password can be set with it's md5 value as well
// MD5(admin) = 21232f297a57a5a743894a0e4a801fc3
// ArduinoOTA.setPasswordHash("21232f297a57a5a743894a0e4a801fc3");
ArduinoOTA ArduinoOTA
.onStart([]() { .onStart([]() {
String type; String type;
@@ -33,28 +25,26 @@ void initOTA(const char* hostname)
type = "filesystem"; type = "filesystem";
// NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end() // NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
Serial.println("Start updating " + type); log_i("Start updating %s", type);
}) })
.onEnd([]() { .onEnd([]() {
Serial.println("\nEnd"); log_i("End");
}) })
.onProgress([](unsigned int progress, unsigned int total) { .onProgress([](unsigned int progress, unsigned int total) {
Serial.printf("Progress: %u%%\r", (progress / (total / 100))); log_i("Progress: %u%%\r", (progress / (total / 100)));
}) })
.onError([](ota_error_t error) { .onError([](ota_error_t error) {
Serial.printf("Error[%u]: ", error); if (error == OTA_AUTH_ERROR) log_e("Auth Failed");
if (error == OTA_AUTH_ERROR) Serial.println("Auth Failed"); else if (error == OTA_BEGIN_ERROR) log_e("Begin Failed");
else if (error == OTA_BEGIN_ERROR) Serial.println("Begin Failed"); else if (error == OTA_CONNECT_ERROR) log_e("Connect Failed");
else if (error == OTA_CONNECT_ERROR) Serial.println("Connect Failed"); else if (error == OTA_RECEIVE_ERROR) log_e("Receive Failed");
else if (error == OTA_RECEIVE_ERROR) Serial.println("Receive Failed"); else if (error == OTA_END_ERROR) log_e("End Failed");
else if (error == OTA_END_ERROR) Serial.println("End Failed"); else log_e("unknown error %i", error);
}); });
ArduinoOTA.begin(); ArduinoOTA.begin();
Serial.println("Ready"); log_i("OTA Ready");
Serial.print("IP address: ");
Serial.println(WiFi.localIP());
} }
void loopOTA() { void loopOTA() {

View File

@@ -5,24 +5,51 @@ WebsocketsServer server;
AsyncWebServer webserver(80); AsyncWebServer webserver(80);
WebsocketsClient client; WebsocketsClient client;
//int LValue, RValue, ArmValue, commaIndex; #define PARAMCOUNT 4
// handle http messages // handle http messages
void handle_message(WebsocketsMessage msg) { void handle_message(WebsocketsMessage msg) {
log_i("%s", msg.data()); log_v("ws data received: %s", msg.data());
uint8_t commaIndex = msg.data().indexOf(','); bool parsing = true;
int LValue = msg.data().substring(0, commaIndex).toInt(); int commaIndex=0, previndex=0;
commaIndex = msg.data().indexOf(',',commaIndex+1); std::vector<int> params;
int RValue = msg.data().substring(commaIndex + 1).toInt();
commaIndex = msg.data().indexOf(',',commaIndex+1);
int ArmValue = msg.data().substring(commaIndex + 1).toInt();
commaIndex = msg.data().indexOf(',',commaIndex+1);
int bucketValue = msg.data().substring(commaIndex + 1).toInt();
drivemotor(0, LValue); while(parsing)
drivemotor(1, RValue); {
drivemotor(2, ArmValue); commaIndex = msg.data().indexOf(',', previndex);
bucketTilt(bucketValue); log_v("commaindex:%i, previndex:%i", commaIndex, previndex);
if(commaIndex == -1)
{
if(previndex > 0)
{
int value = msg.data().substring(previndex + 1).toInt();
log_v("got value(%d): %i", params.size()+1, value);
params.push_back(value);
}
log_v("end of message (param count=%u)", params.size());
parsing = false;
}
else
{
int value = msg.data().substring(previndex, commaIndex).toInt();
log_v("got value(%d): %i", params.size()+1, value);
params.push_back(value);
delay(5);
previndex = commaIndex+1;
}
}
if(params.size() < PARAMCOUNT)
{
log_e("message inclomplete size=%u", params.size());
return;
}
drivemotor(0, params[0]);
drivemotor(1, params[1]);
drivemotor(2, params[2]);
bucketTilt(params[3]);
} }
void setup_webserver() void setup_webserver()
@@ -54,6 +81,14 @@ void loop_webserver()
{ {
client.poll(); client.poll();
} }
else
{
if(!server.available())
{
log_e("server not available");
}
log_w("client not available");
}
webservertimer = millis(); webservertimer = millis();
} }

View File

@@ -11,7 +11,7 @@
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>
#define WEBSERVER_LOOP 50 #define WEBSERVER_LOOP 10
void loop_webserver(); void loop_webserver();
void setup_webserver(); void setup_webserver();