/* implement OpenDroneID MAVLink and DroneCAN support */ /* released under GNU GPL v2 or later */ #include "options.h" #include #include "version.h" #include #include #include #include #include "mavlink.h" #include "DroneCAN.h" #include "WiFi_TX.h" #include "BLE_TX.h" #include "parameters.h" #include "webinterface.h" #include "check_firmware.h" #include #if AP_DRONECAN_ENABLED static DroneCAN dronecan; #endif #if AP_MAVLINK_ENABLED static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0}; static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1}; #endif static WiFi_NAN wifi; static BLE_TX ble; #define DEBUG_BAUDRATE 57600 // OpenDroneID output data structure static ODID_UAS_Data UAS_data; static uint32_t last_location_ms; static WebInterface webif; #include "soc/soc.h" #include "soc/rtc_cntl_reg.h" /* setup serial ports */ void setup() { // disable brownout checking WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); g.init(); // Serial for debug printf Serial.begin(g.baudrate); // Serial1 for MAVLink Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX); // set all fields to invalid/initial values odid_initUasData(&UAS_data); #if AP_MAVLINK_ENABLED mavlink1.init(); mavlink2.init(); #endif #if AP_DRONECAN_ENABLED dronecan.init(); #endif CheckFirmware::check_OTA_running(); #if defined(PIN_CAN_EN) // optional CAN enable pin pinMode(PIN_CAN_EN, OUTPUT); digitalWrite(PIN_CAN_EN, HIGH); #endif #if defined(PIN_CAN_nSILENT) // disable silent pin pinMode(PIN_CAN_nSILENT, OUTPUT); digitalWrite(PIN_CAN_nSILENT, HIGH); #endif #if defined(PIN_CAN_TERM) // optional CAN termination control pinMode(PIN_CAN_TERM, OUTPUT); digitalWrite(PIN_CAN_TERM, HIGH); #endif esp_log_level_set("*", ESP_LOG_DEBUG); esp_ota_mark_app_valid_cancel_rollback(); } #define IMIN(x,y) ((x)<(y)?(x):(y)) #define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from))) /* check parsing of UAS_data, this checks ranges of values to ensure we will produce a valid pack */ static const char *check_parse(void) { { ODID_Location_encoded encoded {}; if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) { return "bad LOCATION data"; } } { ODID_System_encoded encoded {}; if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) { return "bad SYSTEM data"; } } { ODID_BasicID_encoded encoded {}; if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) { return "bad BASIC_ID data"; } } { ODID_SelfID_encoded encoded {}; if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) { return "bad SELF_ID data"; } } { ODID_OperatorID_encoded encoded {}; if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) { return "bad OPERATOR_ID data"; } } return nullptr; } static String escape_string(String s) { s.replace("\"", ""); return s; } /* create a json string from a table */ static String json_format(const json_table_t *table, uint8_t n) { String s = "{"; for (uint8_t i=0; i 5000) { UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; } if (last_system_ms == 0 || now_ms - last_system_ms > 5000) { UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; } if (transport.get_parse_fail() != nullptr) { UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; } set_data(transport); static uint32_t last_update_wifi_ms; if (g.wifi_nan_rate > 0 && now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) { last_update_wifi_ms = now_ms; wifi.transmit(UAS_data); } static uint32_t last_update_bt5_ms; if (g.bt5_rate > 0 && now_ms - last_update_bt5_ms > 1000/g.bt5_rate) { last_update_bt5_ms = now_ms; ble.transmit_longrange(UAS_data); } static uint32_t last_update_bt4_ms; if (g.bt4_rate > 0 && now_ms - last_update_bt4_ms > 200/g.bt4_rate) { last_update_bt4_ms = now_ms; ble.transmit_legacy(UAS_data); ble.transmit_legacy_name(UAS_data); } // sleep for a bit for power saving delay(1); }