Procházet zdrojové kódy

added transport abstraction

simplify common code
Andrew Tridgell před 3 roky
rodič
revize
e7b5081e87

+ 100 - 40
RemoteIDModule/DroneCAN.cpp

@@ -25,10 +25,6 @@
 #define UNUSED(x) (void)(x)
 
 
-// constructor
-DroneCAN::DroneCAN()
-{}
-
 static void onTransferReceived_trampoline(CanardInstance* ins, CanardRxTransfer* transfer);
 static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins, uint64_t* out_data_type_signature, uint16_t data_type_id,
                                             CanardTransferType transfer_type,
@@ -70,8 +66,6 @@ void DroneCAN::node_status_send(void)
     const uint16_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer);
     static uint8_t tx_id;
 
-    Serial.printf("sending NodeStatus len=%u\n", unsigned(len));
-
     canardBroadcast(&canard,
                     UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
                     UAVCAN_PROTOCOL_NODESTATUS_ID,
@@ -86,31 +80,10 @@ void DroneCAN::arm_status_send(void)
     uint8_t buffer[DRONECAN_REMOTEID_ARMSTATUS_MAX_SIZE];
     dronecan_remoteid_ArmStatus arm_status {};
 
-    const uint32_t max_age_location_ms = 3000;
-    const uint32_t max_age_other_ms = 22000;
-    const uint32_t now_ms = millis();
-    const char *reason = "";
-    arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_FAIL_GENERIC;
-    if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
-        reason = "missing location message";
-    } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
-        reason = "missing basic_id message";
-    } else if (last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms) {
-        reason = "missing self_id message";
-    } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
-        reason = "missing operator_id message";
-    } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
-        reason = "missing system message";
-    } else if (msg_Location.latitude == 0 && msg_Location.longitude == 0) {
-        reason = "Bad location";
-    } else if (msg_System.operator_latitude == 0 && msg_System.operator_longitude == 0) {
-        reason = "Bad operator location";
-    } else if (parse_fail != nullptr) {
-        reason = parse_fail;
-    } else {
-        arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_GOOD_TO_ARM;
-    }
+    const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
+    const char *reason = parse_fail==nullptr?"":parse_fail;
 
+    arm_status.status = status;
     arm_status.error.len = strlen(reason);
     strncpy((char*)arm_status.error.data, reason, sizeof(arm_status.error.data));
 
@@ -150,28 +123,23 @@ void DroneCAN::onTransferReceived(CanardInstance* ins,
         break;
     case DRONECAN_REMOTEID_BASICID_ID:
         Serial.printf("Got BasicID\n");
-        dronecan_remoteid_BasicID_decode(transfer, &msg_BasicID);
-        last_basic_id_ms = now_ms;
+        handle_BasicID(transfer);
         break;
     case DRONECAN_REMOTEID_LOCATION_ID:
         Serial.printf("Got Location\n");
-        dronecan_remoteid_Location_decode(transfer, &msg_Location);
-        last_location_ms = now_ms;
+        handle_Location(transfer);
         break;
     case DRONECAN_REMOTEID_SELFID_ID:
         Serial.printf("Got SelfID\n");
-        dronecan_remoteid_SelfID_decode(transfer, &msg_SelfID);
-        last_self_id_ms = now_ms;
+        handle_SelfID(transfer);
         break;
     case DRONECAN_REMOTEID_SYSTEM_ID:
         Serial.printf("Got System\n");
-        dronecan_remoteid_System_decode(transfer, &msg_System);
-        last_system_ms = now_ms;
+        handle_System(transfer);
         break;
     case DRONECAN_REMOTEID_OPERATORID_ID:
         Serial.printf("Got OperatorID\n");
-        dronecan_remoteid_OperatorID_decode(transfer, &msg_OperatorID);
-        last_operator_id_ms = now_ms;
+        handle_OperatorID(transfer);
         break;
     default:
         //Serial.printf("reject %u\n", transfer->data_type_id);
@@ -471,6 +439,98 @@ void DroneCAN::readUniqueID(uint8_t id[6])
     esp_efuse_mac_get_default(id);
 }
 
+#define IMIN(a,b) ((a)<(b)?(a):(b))
+#define COPY_FIELD(fname) mpkt.fname = pkt.fname
+#define COPY_STR(fname) memcpy(mpkt.fname, pkt.fname.data, IMIN(pkt.fname.len, sizeof(mpkt.fname)))
+
+void DroneCAN::handle_BasicID(CanardRxTransfer* transfer)
+{
+    dronecan_remoteid_BasicID pkt {};
+    auto &mpkt = basic_id;
+    dronecan_remoteid_BasicID_decode(transfer, &pkt);
+    last_basic_id_ms = millis();
+    memset(&mpkt, 0, sizeof(mpkt));
+    COPY_STR(id_or_mac);
+    COPY_FIELD(id_type);
+    COPY_FIELD(ua_type);
+    COPY_STR(uas_id);
+}
+
+void DroneCAN::handle_SelfID(CanardRxTransfer* transfer)
+{
+    dronecan_remoteid_SelfID pkt {};
+    auto &mpkt = self_id;
+    dronecan_remoteid_SelfID_decode(transfer, &pkt);
+    last_self_id_ms = millis();
+    memset(&mpkt, 0, sizeof(mpkt));
+    COPY_STR(id_or_mac);
+    COPY_FIELD(description_type);
+    COPY_STR(description);
+}
+
+void DroneCAN::handle_System(CanardRxTransfer* transfer)
+{
+    dronecan_remoteid_System pkt {};
+    auto &mpkt = system;
+    dronecan_remoteid_System_decode(transfer, &pkt);
+    last_system_ms = millis();
+    memset(&mpkt, 0, sizeof(mpkt));
+
+    COPY_STR(id_or_mac);
+    COPY_FIELD(operator_location_type);
+    COPY_FIELD(classification_type);
+    COPY_FIELD(operator_latitude);
+    COPY_FIELD(operator_longitude);
+    COPY_FIELD(area_count);
+    COPY_FIELD(area_radius);
+    COPY_FIELD(area_ceiling);
+    COPY_FIELD(area_floor);
+    COPY_FIELD(category_eu);
+    COPY_FIELD(class_eu);
+    COPY_FIELD(operator_altitude_geo);
+    COPY_FIELD(timestamp);
+}
+
+void DroneCAN::handle_OperatorID(CanardRxTransfer* transfer)
+{
+    dronecan_remoteid_OperatorID pkt {};
+    auto &mpkt = operator_id;
+    dronecan_remoteid_OperatorID_decode(transfer, &pkt);
+    last_operator_id_ms = millis();
+    memset(&mpkt, 0, sizeof(mpkt));
+
+    COPY_STR(id_or_mac);
+    COPY_FIELD(operator_id_type);
+    COPY_STR(operator_id);
+}
+
+void DroneCAN::handle_Location(CanardRxTransfer* transfer)
+{
+    dronecan_remoteid_Location pkt {};
+    auto &mpkt = location;
+    dronecan_remoteid_Location_decode(transfer, &pkt);
+    last_location_ms = millis();
+    memset(&mpkt, 0, sizeof(mpkt));
+
+    COPY_STR(id_or_mac);
+    COPY_FIELD(status);
+    COPY_FIELD(direction);
+    COPY_FIELD(speed_horizontal);
+    COPY_FIELD(speed_vertical);
+    COPY_FIELD(latitude);
+    COPY_FIELD(longitude);
+    COPY_FIELD(altitude_barometric);
+    COPY_FIELD(altitude_geodetic);
+    COPY_FIELD(height_reference);
+    COPY_FIELD(height);
+    COPY_FIELD(horizontal_accuracy);
+    COPY_FIELD(vertical_accuracy);
+    COPY_FIELD(barometer_accuracy);
+    COPY_FIELD(speed_accuracy);
+    COPY_FIELD(timestamp);
+    COPY_FIELD(timestamp_accuracy);
+}
+
 #if 0
 // xprintf is useful when debugging in C code such as libcanard
 extern "C" {

+ 13 - 33
RemoteIDModule/DroneCAN.h

@@ -1,5 +1,6 @@
 
 #include "CANDriver.h"
+#include "transport.h"
 #include <canard.h>
 
 #include <canard.h>
@@ -12,20 +13,12 @@
 
 #define CAN_POOL_SIZE 4096
 
-class DroneCAN {
+class DroneCAN : public Transport {
 public:
-    DroneCAN();
-    void init(void);
-    void update(void);
-
-    void set_parse_fail(const char *msg) {
-        parse_fail = msg;
-    }
-
-    uint32_t get_last_location_ms(void) {
-        return last_location_ms;
-    }
-    
+    using Transport::Transport;
+    void init(void) override;
+    void update(void) override;
+
 private:
     uint32_t last_node_status_ms;
     CANDriver can_driver;
@@ -56,20 +49,13 @@ private:
     uint32_t last_DNA_start_ms;
 
     uavcan_protocol_NodeStatus node_status;
-    dronecan_remoteid_BasicID msg_BasicID;
-    dronecan_remoteid_Location msg_Location;
-    dronecan_remoteid_SelfID msg_SelfID;
-    dronecan_remoteid_System msg_System;
-    dronecan_remoteid_OperatorID msg_OperatorID;
-
-    uint32_t last_location_ms;
-    uint32_t last_basic_id_ms;
-    uint32_t last_self_id_ms;
-    uint32_t last_operator_id_ms;
-    uint32_t last_system_ms;
-
-    const char *parse_fail;
-    
+
+    void handle_BasicID(CanardRxTransfer* transfer);
+    void handle_SelfID(CanardRxTransfer* transfer);
+    void handle_OperatorID(CanardRxTransfer* transfer);
+    void handle_System(CanardRxTransfer* transfer);
+    void handle_Location(CanardRxTransfer* transfer);
+
 public:
     void onTransferReceived(CanardInstance* ins, CanardRxTransfer* transfer);
     bool shouldAcceptTransfer(const CanardInstance* ins,
@@ -77,10 +63,4 @@ public:
                               uint16_t data_type_id,
                               CanardTransferType transfer_type,
                               uint8_t source_node_id);
-
-    const dronecan_remoteid_BasicID &get_basic_id(void) { return msg_BasicID; }
-    const dronecan_remoteid_Location &get_location(void) { return msg_Location; }
-    const dronecan_remoteid_SelfID &get_self_id(void) { return msg_SelfID; }
-    const dronecan_remoteid_System &get_system(void) { return msg_System; }
-    const dronecan_remoteid_OperatorID &get_operator_id(void) { return msg_OperatorID; }
 };

+ 29 - 112
RemoteIDModule/RemoteIDModule.ino

@@ -136,13 +136,16 @@ static const char *check_parse(void)
     return nullptr;
 }
 
-static void set_data_mavlink(MAVLinkSerial &m)
+/*
+  fill in UAS_data from MAVLink packets
+ */
+static void set_data(Transport &t)
 {
-    const auto &operator_id = m.get_operator_id();
-    const auto &basic_id = m.get_basic_id();
-    const auto &system = m.get_system();
-    const auto &self_id = m.get_self_id();
-    const auto &location = m.get_location();
+    const auto &operator_id = t.get_operator_id();
+    const auto &basic_id = t.get_basic_id();
+    const auto &system = t.get_system();
+    const auto &self_id = t.get_self_id();
+    const auto &location = t.get_location();
 
     // BasicID
     UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
@@ -198,92 +201,25 @@ static void set_data_mavlink(MAVLinkSerial &m)
         UAS_data.LocationValid = 1;
     }
 
-    m.set_parse_fail(check_parse());
-
-    uint32_t now_ms = millis();
-    uint32_t location_age_ms = now_ms - m.get_last_location_ms();
-    uint32_t last_location_age_ms = now_ms - last_location_ms;
-    if (location_age_ms < last_location_age_ms) {
-        last_location_ms = m.get_last_location_ms();
-    }
-}
-
-#undef ODID_COPY_STR
-#define ODID_COPY_STR(to, from) memcpy(to, from.data, IMIN(from.len, sizeof(to)))
-
-#if AP_DRONECAN_ENABLED
-static void set_data_dronecan(void)
-{
-    const auto &operator_id = dronecan.get_operator_id();
-    const auto &basic_id = dronecan.get_basic_id();
-    const auto &system = dronecan.get_system();
-    const auto &self_id = dronecan.get_self_id();
-    const auto &location = dronecan.get_location();
-
-    // BasicID
-    UAS_data.BasicID[0].UAType = (ODID_uatype_t)basic_id.ua_type;
-    UAS_data.BasicID[0].IDType = (ODID_idtype_t)basic_id.id_type;
-    ODID_COPY_STR(UAS_data.BasicID[0].UASID, basic_id.uas_id);
-    UAS_data.BasicIDValid[0] = 1;
-
-    // OperatorID
-    UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
-    ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
-    UAS_data.OperatorIDValid = 1;
-
-    // SelfID
-    UAS_data.SelfID.DescType = (ODID_desctype_t)self_id.description_type;
-    ODID_COPY_STR(UAS_data.SelfID.Desc, self_id.description);
-    UAS_data.SelfIDValid = 1;
-
-    // System
-    if (system.timestamp != 0) {
-        UAS_data.System.OperatorLocationType = (ODID_operator_location_type_t)system.operator_location_type;
-        UAS_data.System.ClassificationType = (ODID_classification_type_t)system.classification_type;
-        UAS_data.System.OperatorLatitude = system.operator_latitude * 1.0e-7;
-        UAS_data.System.OperatorLongitude = system.operator_longitude * 1.0e-7;
-        UAS_data.System.AreaCount = system.area_count;
-        UAS_data.System.AreaRadius = system.area_radius;
-        UAS_data.System.AreaCeiling = system.area_ceiling;
-        UAS_data.System.AreaFloor = system.area_floor;
-        UAS_data.System.CategoryEU = (ODID_category_EU_t)system.category_eu;
-        UAS_data.System.ClassEU = (ODID_class_EU_t)system.class_eu;
-        UAS_data.System.OperatorAltitudeGeo = system.operator_altitude_geo;
-        UAS_data.System.Timestamp = system.timestamp;
-        UAS_data.SystemValid = 1;
-    }
-
-    // Location
-    if (location.timestamp != 0) {
-        UAS_data.Location.Status = (ODID_status_t)location.status;
-        UAS_data.Location.Direction = location.direction*0.01;
-        UAS_data.Location.SpeedHorizontal = location.speed_horizontal*0.01;
-        UAS_data.Location.SpeedVertical = location.speed_vertical*0.01;
-        UAS_data.Location.Latitude = location.latitude*1.0e-7;
-        UAS_data.Location.Longitude = location.longitude*1.0e-7;
-        UAS_data.Location.AltitudeBaro = location.altitude_barometric;
-        UAS_data.Location.AltitudeGeo = location.altitude_geodetic;
-        UAS_data.Location.HeightType = (ODID_Height_reference_t)location.height_reference;
-        UAS_data.Location.Height = location.height;
-        UAS_data.Location.HorizAccuracy = (ODID_Horizontal_accuracy_t)location.horizontal_accuracy;
-        UAS_data.Location.VertAccuracy = (ODID_Vertical_accuracy_t)location.vertical_accuracy;
-        UAS_data.Location.BaroAccuracy = (ODID_Vertical_accuracy_t)location.barometer_accuracy;
-        UAS_data.Location.SpeedAccuracy = (ODID_Speed_accuracy_t)location.speed_accuracy;
-        UAS_data.Location.TSAccuracy = (ODID_Timestamp_accuracy_t)location.timestamp_accuracy;
-        UAS_data.Location.TimeStamp = location.timestamp;
-        UAS_data.LocationValid = 1;
+    const char *reason = check_parse();
+    if (reason == nullptr) {
+        t.arm_status_check(reason);
     }
+    t.set_parse_fail(reason);
 
-    dronecan.set_parse_fail(check_parse());
+#ifdef PIN_STATUS_LED
+    // LED off if good to arm
+    pinMode(PIN_STATUS_LED, OUTPUT);
+    digitalWrite(PIN_STATUS_LED, reason==nullptr?!STATUS_LED_ON:STATUS_LED_ON);
+#endif
 
     uint32_t now_ms = millis();
-    uint32_t location_age_ms = now_ms - dronecan.get_last_location_ms();
+    uint32_t location_age_ms = now_ms - t.get_last_location_ms();
     uint32_t last_location_age_ms = now_ms - last_location_ms;
     if (location_age_ms < last_location_age_ms) {
-        last_location_ms = dronecan.get_last_location_ms();
+        last_location_ms = t.get_last_location_ms();
     }
 }
-#endif // AP_DRONECAN_ENABLED
 
 void loop()
 {
@@ -302,18 +238,12 @@ void loop()
         return;
     }
 
-    bool have_location = false;
-
-#if AP_MAVLINK_ENABLED
-    const bool mavlink1_ok = mavlink1.get_last_location_ms() != 0;
-    const bool mavlink2_ok = mavlink2.get_last_location_ms() != 0;
-    have_location |= mavlink1_ok || mavlink2_ok;
-#endif
+    // the transports have common static data, so we can just use the
+    // first for status
+    auto &transport = mavlink1;
 
-#if AP_DRONECAN_ENABLED
-    const bool dronecan_ok = dronecan.get_last_location_ms() != 0;
-    have_location |= dronecan_ok;
-#endif
+    bool have_location = false;
+    const uint32_t last_location_ms = transport.get_last_location_ms();
 
 #if AP_BROADCAST_ON_POWER_UP
     // if we are broadcasting on powerup we always mark location valid
@@ -324,30 +254,17 @@ void loop()
     }
 #else
     // only broadcast if we have received a location at least once
-    if (!have_location) {
+    if (last_location_ms == 0) {
         return;
     }
 #endif
 
-    if (now_ms - last_location_ms > 5000) {
+    if (last_location_ms == 0 ||
+        now_ms - last_location_ms > 5000) {
         UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
     }
 
-#if AP_MAVLINK_ENABLED
-    if (mavlink1_ok) {
-        set_data_mavlink(mavlink1);
-    }
-    if (mavlink2_ok) {
-        set_data_mavlink(mavlink2);
-    }
-#endif
-
-#if AP_DRONECAN_ENABLED
-    if (dronecan_ok) {
-        set_data_dronecan();
-    }
-#endif
-
+    set_data(transport);
     last_update = now_ms;
 
 #if AP_WIFI_NAN_ENABLED

+ 2 - 33
RemoteIDModule/mavlink.cpp

@@ -163,39 +163,8 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
 
 void MAVLinkSerial::arm_status_send(void)
 {
-    const uint32_t max_age_location_ms = 3000;
-    const uint32_t max_age_other_ms = 22000;
-    const uint32_t now_ms = millis();
-    const char *reason = "";
-    uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
-
-    if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
-        reason = "missing location message";
-    } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
-        reason = "missing basic_id message";
-    } else if (last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms) {
-        reason = "missing self_id message";
-    } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
-        reason = "missing operator_id message";
-    } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
-        reason = "missing system message";
-    } else if (location.latitude == 0 && location.longitude == 0) {
-        reason = "Bad location";
-    } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
-        reason = "Bad operator location";
-    } else if (parse_fail != nullptr) {
-        reason = parse_fail;
-    } else {
-        status = MAV_ODID_GOOD_TO_ARM;
-    }
-
-#ifdef PIN_STATUS_LED
-        // LED off if good to arm
-        pinMode(PIN_STATUS_LED, OUTPUT);
-        digitalWrite(PIN_STATUS_LED, status==MAV_ODID_GOOD_TO_ARM?!STATUS_LED_ON:STATUS_LED_ON);
-#endif
-
-    
+    const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
+    const char *reason = parse_fail==nullptr?"":parse_fail;
     mavlink_msg_open_drone_id_arm_status_send(
         chan,
         status,

+ 6 - 72
RemoteIDModule/mavlink.h

@@ -2,75 +2,17 @@
   mavlink class for handling OpenDroneID messages
  */
 #pragma once
-
-// we have separate helpers disabled to make it possible
-// to select MAVLink 1.0 in the arduino GUI build
-#define MAVLINK_SEPARATE_HELPERS
-#define MAVLINK_NO_CONVERSION_HELPERS
-
-#define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
-
-// two buffers, one for USB, one for UART. This makes for easier testing with SITL
-#define MAVLINK_COMM_NUM_BUFFERS 2
-
-#define MAVLINK_MAX_PAYLOAD_LEN 255
-
-#include <mavlink2.h>
-
-/// MAVLink system definition
-extern mavlink_system_t mavlink_system;
-
-void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
-
-#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
-#include <generated/all/mavlink.h>
+#include "transport.h"
 
 /*
   abstraction for MAVLink on a serial port
  */
-class MAVLinkSerial {
+class MAVLinkSerial : public Transport {
 public:
+    using Transport::Transport;
     MAVLinkSerial(HardwareSerial &serial, mavlink_channel_t chan);
-    void init(void);
-    void update(void);
-
-    const mavlink_open_drone_id_location_t &get_location(void) const {
-        return location;
-    }
-
-    const mavlink_open_drone_id_basic_id_t &get_basic_id(void) const {
-        return basic_id;
-    }
-
-    const mavlink_open_drone_id_authentication_t &get_authentication(void) const {
-        return authentication;
-    }
-
-    const mavlink_open_drone_id_self_id_t &get_self_id(void) const {
-        return self_id;
-    }
-
-    const mavlink_open_drone_id_system_t &get_system(void) const {
-        return system;
-    }
-
-    const mavlink_open_drone_id_operator_id_t &get_operator_id(void) const {
-        return operator_id;
-    }
-
-    uint32_t last_location_ms;
-    uint32_t last_basic_id_ms;
-    uint32_t last_self_id_ms;
-    uint32_t last_operator_id_ms;
-    uint32_t last_system_ms;
-
-    uint32_t get_last_location_ms(void) {
-        return last_location_ms;
-    }
-
-    void set_parse_fail(const char *msg) {
-        parse_fail = msg;
-    }
+    void init(void) override;
+    void update(void) override;
 
 private:
     HardwareSerial &serial;
@@ -81,14 +23,6 @@ private:
     void update_send(void);
     void process_packet(mavlink_status_t &status, mavlink_message_t &msg);
     void mav_printf(uint8_t severity, const char *fmt, ...);
-    void arm_status_send(void);
 
-    mavlink_open_drone_id_location_t location;
-    mavlink_open_drone_id_basic_id_t basic_id;
-    mavlink_open_drone_id_authentication_t authentication;
-    mavlink_open_drone_id_self_id_t self_id;
-    mavlink_open_drone_id_system_t system;
-    mavlink_open_drone_id_operator_id_t operator_id;
-
-    const char *parse_fail;
+    void arm_status_send(void);
 };

+ 26 - 0
RemoteIDModule/mavlink_msgs.h

@@ -0,0 +1,26 @@
+/*
+  mavlink message definitions
+ */
+#pragma once
+
+// we have separate helpers disabled to make it possible
+// to select MAVLink 1.0 in the arduino GUI build
+#define MAVLINK_SEPARATE_HELPERS
+#define MAVLINK_NO_CONVERSION_HELPERS
+
+#define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
+
+// two buffers, one for USB, one for UART. This makes for easier testing with SITL
+#define MAVLINK_COMM_NUM_BUFFERS 2
+
+#define MAVLINK_MAX_PAYLOAD_LEN 255
+
+#include <mavlink2.h>
+
+/// MAVLink system definition
+extern mavlink_system_t mavlink_system;
+
+void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
+
+#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
+#include <generated/all/mavlink.h>

+ 58 - 0
RemoteIDModule/transport.cpp

@@ -0,0 +1,58 @@
+/*
+  generic transport class for handling OpenDroneID messages
+ */
+#include <Arduino.h>
+#include "transport.h"
+
+const char *Transport::parse_fail = "uninitialised";
+
+uint32_t Transport::last_location_ms;
+uint32_t Transport::last_basic_id_ms;
+uint32_t Transport::last_self_id_ms;
+uint32_t Transport::last_operator_id_ms;
+uint32_t Transport::last_system_ms;
+
+mavlink_open_drone_id_location_t Transport::location;
+mavlink_open_drone_id_basic_id_t Transport::basic_id;
+mavlink_open_drone_id_authentication_t Transport::authentication;
+mavlink_open_drone_id_self_id_t Transport::self_id;
+mavlink_open_drone_id_system_t Transport::system;
+mavlink_open_drone_id_operator_id_t Transport::operator_id;
+
+Transport::Transport()
+{
+}
+
+/*
+  check we are OK to arm
+ */
+uint8_t Transport::arm_status_check(const char *&reason)
+{
+    const uint32_t max_age_location_ms = 3000;
+    const uint32_t max_age_other_ms = 22000;
+    const uint32_t now_ms = millis();
+
+    uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
+
+    if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
+        reason = "missing location message";
+    } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
+        reason = "missing basic_id message";
+    } else if (last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms) {
+        reason = "missing self_id message";
+    } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
+        reason = "missing operator_id message";
+    } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
+        // we use location age limit for system as the operator location needs to come in as fast
+        // as the vehicle location for FAA standard
+        reason = "missing system message";
+    } else if (location.latitude == 0 && location.longitude == 0) {
+        reason = "Bad location";
+    } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
+        reason = "Bad operator location";
+    } else if (reason == nullptr) {
+        status = MAV_ODID_GOOD_TO_ARM;
+    }
+
+    return status;
+}

+ 67 - 0
RemoteIDModule/transport.h

@@ -0,0 +1,67 @@
+/*
+  parent class for handling transports
+ */
+#pragma once
+
+#include "mavlink_msgs.h"
+
+/*
+  abstraction for opendroneid transports
+ */
+class Transport {
+public:
+    Transport();
+    virtual void init(void) = 0;
+    virtual void update(void) = 0;
+    uint8_t arm_status_check(const char *&reason);
+
+    const mavlink_open_drone_id_location_t &get_location(void) const {
+        return location;
+    }
+
+    const mavlink_open_drone_id_basic_id_t &get_basic_id(void) const {
+        return basic_id;
+    }
+
+    const mavlink_open_drone_id_authentication_t &get_authentication(void) const {
+        return authentication;
+    }
+
+    const mavlink_open_drone_id_self_id_t &get_self_id(void) const {
+        return self_id;
+    }
+
+    const mavlink_open_drone_id_system_t &get_system(void) const {
+        return system;
+    }
+
+    const mavlink_open_drone_id_operator_id_t &get_operator_id(void) const {
+        return operator_id;
+    }
+
+    uint32_t get_last_location_ms(void) const {
+        return last_location_ms;
+    }
+
+    void set_parse_fail(const char *msg) {
+        parse_fail = msg;
+    }
+
+protected:
+    // common variables between transports. The last message of each
+    // type, no matter what transport it was on, wins
+    static const char *parse_fail;
+
+    static uint32_t last_location_ms;
+    static uint32_t last_basic_id_ms;
+    static uint32_t last_self_id_ms;
+    static uint32_t last_operator_id_ms;
+    static uint32_t last_system_ms;
+
+    static mavlink_open_drone_id_location_t location;
+    static mavlink_open_drone_id_basic_id_t basic_id;
+    static mavlink_open_drone_id_authentication_t authentication;
+    static mavlink_open_drone_id_self_id_t self_id;
+    static mavlink_open_drone_id_system_t system;
+    static mavlink_open_drone_id_operator_id_t operator_id;
+};