Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -20,18 +20,23 @@
# The upload speed below (921600) has worked fine for all modules I tested. If you have upload issues,
# try reducing to 115200.

[version]
build_flags = !echo "-DPIO_SRC_REV="$(git rev-parse HEAD) "-DPIO_BUILD_DATE="$(date +%%Y-%%m-%%d) "-DPIO_BUILD_TIME="$(date +%%H:%%M:%%S)

[env:esp12e]
platform = espressif8266
framework = arduino
board = esp12e
build_flags = -Wl,-Tesp8266.flash.4m.ld
build_flags = ${version.build_flags} -Wl,-Tesp8266.flash.4m.ld

[env:esp01_1m]
platform = espressif8266
framework = arduino
board = esp01_1m
build_flags = ${version.build_flags}

[env:esp01]
platform = espressif8266
framework = arduino
board = esp01
build_flags = ${version.build_flags}
3 changes: 1 addition & 2 deletions src/mavesp8266.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ struct linkStatus {
uint32_t packets_received;
uint32_t packets_lost;
uint32_t packets_sent;
uint32_t parse_errors;
uint32_t radio_status_sent;
uint8_t queue_status;
};
Expand All @@ -96,7 +97,6 @@ class MavESP8266Bridge {
virtual void begin (MavESP8266Bridge* forwardTo);
virtual void readMessage () = 0;
virtual void readMessageRaw () = 0;
virtual int sendMessage (mavlink_message_t* message, int count) = 0;
virtual int sendMessage (mavlink_message_t* message) = 0;
virtual int sendMessageRaw (uint8_t *buffer, int len) = 0;
virtual bool heardFrom () { return _heard_from; }
Expand All @@ -107,7 +107,6 @@ class MavESP8266Bridge {
mavlink_channel_t _recv_chan;
protected:
virtual void _checkLinkErrors(mavlink_message_t* msg);
virtual void _sendRadioStatus() = 0;
protected:
bool _heard_from;
uint8_t _system_id;
Expand Down
89 changes: 41 additions & 48 deletions src/mavesp8266_gcs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,12 +73,16 @@ MavESP8266GCS::readMessage()
_forwardTo->sendMessage(&_message);
memset(&_message, 0, sizeof(_message));
}
uint32_t now = millis();
//-- Update radio status (1Hz)
if(_heard_from && (millis() - _last_status_time > 1000)) {
if(_heard_from && (now - _last_status_time > 1000)) {
delay(0);
_sendRadioStatus();
_last_status_time = millis();
}
if (_sendbuf_ofs > 0 && (now - _send_start_ms > UDP_QUEUE_TIMEOUT || _packets_queued >= 20)) {
_send_pending();
}
}


Expand All @@ -97,11 +101,15 @@ MavESP8266GCS::_readMessage()
if (result >= 0)
{
// Parsing
uint8_t last_parse_error = _rxstatus.parse_error;
msgReceived = mavlink_frame_char_buffer(&_rxmsg,
&_rxstatus,
result,
&_message,
&_mav_status);
if (last_parse_error != _rxstatus.parse_error) {
_status.parse_errors++;
}
if(msgReceived) {
//-- We no longer need to broadcast
_status.packets_received++;
Expand All @@ -128,14 +136,19 @@ MavESP8266GCS::_readMessage()
_checkLinkErrors(&_message);
}

if (msgReceived == MAVLINK_FRAMING_BAD_CRC ||
msgReceived == MAVLINK_FRAMING_BAD_SIGNATURE) {
if (msgReceived == MAVLINK_FRAMING_BAD_CRC) {
// we don't process messages locally with bad CRC,
// but we do forward them, so when new messages
// are added we can bridge them
break;
}

#ifdef MAVLINK_FRAMING_BAD_SIGNATURE
if (msgReceived == MAVLINK_FRAMING_BAD_SIGNATURE) {
break;
}
#endif

//-- Check for message we might be interested
if(getWorld()->getComponent()->handleMessage(this, &_message)){
//-- Eat message (don't send it to FC)
Expand Down Expand Up @@ -192,36 +205,6 @@ MavESP8266GCS::readMessageRaw() {
}
}

//---------------------------------------------------------------------------------
//-- Forward message(s) to the GCS
int
MavESP8266GCS::sendMessage(mavlink_message_t* message, int count) {
int sentCount = 0;
_udp.beginPacket(_ip, _udp_port);
for(int i = 0; i < count; i++) {
// Translate message to buffer
char buf[300];
unsigned len = mavlink_msg_to_send_buffer((uint8_t*)buf, &message[i]);
// Send it
_status.packets_sent++;
size_t sent = _udp.write((uint8_t*)(void*)buf, len);
if(sent != len) {
break;
//-- Fibble attempt at not losing data until we get access to the socket TX buffer
// status before we try to send.
_udp.endPacket();
delay(2);
_udp.beginPacket(_ip, _udp_port);
_udp.write((uint8_t*)(void*)&buf[sent], len - sent);
_udp.endPacket();
return sentCount;
}
sentCount++;
}
_udp.endPacket();
return sentCount;
}

//---------------------------------------------------------------------------------
//-- Forward message to the GCS
int
Expand All @@ -231,11 +214,11 @@ MavESP8266GCS::sendMessage(mavlink_message_t* message) {
}

int
MavESP8266GCS::sendMessageRaw(uint8_t *buffer, int len) {
MavESP8266GCS::sendMessageRaw(uint8_t *buffer, int len)
{
_udp.beginPacket(_ip, _udp_port);
size_t sent = _udp.write(buffer, len);
_udp.endPacket();
//_udp.flush();
return sent;
}

Expand Down Expand Up @@ -270,7 +253,7 @@ MavESP8266GCS::_sendRadioStatus()
&msg,
rssi, // RSSI Only valid in STA mode
0, // We don't have access to Remote RSSI
st->queue_status, // UDP queue status
100,
0, // We don't have access to noise data
lostVehicleMessages, // Percent of lost messages from Vehicle (UART)
lostGcsMessages, // Percent of lost messages from GCS (UDP)
Expand All @@ -289,17 +272,27 @@ MavESP8266GCS::_sendSingleUdpMessage(mavlink_message_t* msg)
// Translate message to buffer
char buf[300];
unsigned len = mavlink_msg_to_send_buffer((uint8_t*)buf, msg);
// Send it
_udp.beginPacket(_ip, _udp_port);
size_t sent = _udp.write((uint8_t*)(void*)buf, len);
_udp.endPacket();
//-- Fibble attempt at not losing data until we get access to the socket TX buffer
// status before we try to send.
if(sent != len) {
delay(1);
_udp.beginPacket(_ip, _udp_port);
_udp.write((uint8_t*)(void*)&buf[sent], len - sent);
_udp.endPacket();
if (len + _sendbuf_ofs > sizeof(_sendbuf)) {
_send_pending();
}
memcpy(&_sendbuf[_sendbuf_ofs], buf, len);
if (_sendbuf_ofs == 0) {
_send_start_ms = millis();
}
_packets_queued++;
_sendbuf_ofs += len;
}

/*
send pending data in _sendbuf
*/
void MavESP8266GCS::_send_pending(void)
{
if (_sendbuf_ofs > 0) {
if (sendMessageRaw(_sendbuf, _sendbuf_ofs) == _sendbuf_ofs) {
_sendbuf_ofs = 0;
_status.packets_sent += _packets_queued;
_packets_queued = 0;
}
}
_status.packets_sent++;
}
9 changes: 8 additions & 1 deletion src/mavesp8266_gcs.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@
#ifndef MAVESP8266_GCS_H
#define MAVESP8266_GCS_H

//-- UDP Outgoing buffer timeout
#define UDP_QUEUE_TIMEOUT 5 // 5ms

#include "mavesp8266.h"

class MavESP8266GCS : public MavESP8266Bridge {
Expand All @@ -47,7 +50,6 @@ class MavESP8266GCS : public MavESP8266Bridge {
void begin (MavESP8266Bridge* forwardTo, IPAddress gcsIP);
void readMessage ();
void readMessageRaw ();
int sendMessage (mavlink_message_t* message, int count);
int sendMessage (mavlink_message_t* message);
int sendMessageRaw (uint8_t *buffer, int len);
protected:
Expand All @@ -57,13 +59,18 @@ class MavESP8266GCS : public MavESP8266Bridge {
bool _readMessage ();
void _sendSingleUdpMessage (mavlink_message_t* msg);
void _checkUdpErrors (mavlink_message_t* msg);
void _send_pending ();

private:
WiFiUDP _udp;
IPAddress _ip;
uint16_t _udp_port;
mavlink_message_t _message;
unsigned long _last_status_time;
uint8_t _sendbuf[1400];
uint16_t _sendbuf_ofs;
uint16_t _packets_queued;
uint32_t _send_start_ms;
};

#endif
20 changes: 20 additions & 0 deletions src/mavesp8266_httpd.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,13 @@ const char* kFlashMaps[7] = {
"4MB (1024/1024)"
};

// convert git version and build date to string
#define str(s) #s
#define xstr(s) str(s)
#define GIT_VERSION_STRING xstr(PIO_SRC_REV)
#define BUILD_DATE_STRING xstr(PIO_BUILD_DATE)
#define BUILD_TIME_STRING xstr(PIO_BUILD_TIME)

static uint32_t flash = 0;
static char paramCRC[12] = {""};

Expand Down Expand Up @@ -134,6 +141,7 @@ void handle_upload_status() {
DEBUG_SERIAL.setDebugOutput(true);
#endif
WiFiUDP::stopAll();
Serial.end();
#ifdef DEBUG_SERIAL
DEBUG_SERIAL.printf("Update: %s\n", upload.filename.c_str());
#endif
Expand Down Expand Up @@ -207,6 +215,14 @@ static void handle_root()
char vstr[30];
snprintf(vstr, sizeof(vstr), "%u.%u.%u", MAVESP8266_VERSION_MAJOR, MAVESP8266_VERSION_MINOR, MAVESP8266_VERSION_BUILD);
message += vstr;
message += "<br>\n";
message += "Git Version: ";
message += GIT_VERSION_STRING;
message += "<br>\n";
message += "Build Date: ";
message += BUILD_DATE_STRING;
message += " ";
message += BUILD_TIME_STRING;
message += "<p>\n";
message += "<ul>\n";
message += "<li><a href='/getstatus'>Get Status</a>\n";
Expand Down Expand Up @@ -321,12 +337,16 @@ static void handle_getStatus()
message += gcsStatus->packets_sent;
message += "</td></tr><tr><td>GCS Packets Lost</td><td>";
message += gcsStatus->packets_lost;
message += "</td></tr><tr><td>GCS Parse Errors</td><td>";
message += gcsStatus->parse_errors;
message += "</td></tr><tr><td>Packets Received from Vehicle</td><td>";
message += vehicleStatus->packets_received;
message += "</td></tr><tr><td>Packets Sent to Vehicle</td><td>";
message += vehicleStatus->packets_sent;
message += "</td></tr><tr><td>Vehicle Packets Lost</td><td>";
message += vehicleStatus->packets_lost;
message += "</td></tr><tr><td>Vehicle Parse Errors</td><td>";
message += vehicleStatus->parse_errors;
message += "</td></tr><tr><td>Radio Messages</td><td>";
message += gcsStatus->radio_status_sent;
message += "</td></tr></table>";
Expand Down
Loading