Browse Source

more specific error messages

and fixed CAN send timeout
Andrew Tridgell 3 years ago
parent
commit
ef06e0df94
4 changed files with 25 additions and 25 deletions
  1. 2 6
      RemoteIDModule/CANDriver.cpp
  2. 11 8
      RemoteIDModule/DroneCAN.cpp
  3. 12 9
      RemoteIDModule/mavlink.cpp
  4. 0 2
      RemoteIDModule/mavlink.h

+ 2 - 6
RemoteIDModule/CANDriver.cpp

@@ -224,18 +224,14 @@ bool CANDriver::send(const CANFrame &frame)
     message.data_length_code = frame.dlc;
     message.data_length_code = frame.dlc;
     memcpy(message.data, frame.data, 8);
     memcpy(message.data, frame.data, 8);
 
 
-    esp_err_t sts = twai_transmit(&message, portMAX_DELAY);
-    ESP_ERROR_CHECK(sts);
-
+    const esp_err_t sts = twai_transmit(&message, pdMS_TO_TICKS(2));
     return (sts == ESP_OK);
     return (sts == ESP_OK);
 }
 }
 
 
 bool CANDriver::receive(CANFrame &out_frame)
 bool CANDriver::receive(CANFrame &out_frame)
 {
 {
-#define MAX_RECV_MSGS_PER_SEC 200
-
     twai_message_t message {};
     twai_message_t message {};
-    esp_err_t recverr = twai_receive(&message, pdMS_TO_TICKS(1000/MAX_RECV_MSGS_PER_SEC));
+    esp_err_t recverr = twai_receive(&message, pdMS_TO_TICKS(2));
     if (recverr != ESP_OK) {
     if (recverr != ESP_OK) {
         return false;
         return false;
     }
     }

+ 11 - 8
RemoteIDModule/DroneCAN.cpp

@@ -84,16 +84,20 @@ void DroneCAN::arm_status_send(void)
     dronecan_remoteid_ArmStatus arm_status {};
     dronecan_remoteid_ArmStatus arm_status {};
 
 
     const uint32_t max_age_location_ms = 3000;
     const uint32_t max_age_location_ms = 3000;
-    const uint32_t max_age_other_ms = 2200;
+    const uint32_t max_age_other_ms = 22000;
     const uint32_t now_ms = millis();
     const uint32_t now_ms = millis();
     const char *reason = "";
     const char *reason = "";
     arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_FAIL_GENERIC;
     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 ||
-        last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms ||
-        last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms ||
-        last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms ||
-        last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
-        reason = "missing ODID messages";
+    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) {
     } else if (msg_Location.latitude == 0 && msg_Location.longitude == 0) {
         reason = "Bad location";
         reason = "Bad location";
     } else if (msg_System.operator_latitude == 0 && msg_System.operator_longitude == 0) {
     } else if (msg_System.operator_latitude == 0 && msg_System.operator_longitude == 0) {
@@ -233,7 +237,6 @@ void DroneCAN::processTx(void)
             canardPopTxQueue(&canard);
             canardPopTxQueue(&canard);
             tx_fail_count = 0;
             tx_fail_count = 0;
         } else {
         } else {
-            Serial.printf("can send fail\n");
             if (tx_fail_count < 8) {
             if (tx_fail_count < 8) {
                 tx_fail_count++;
                 tx_fail_count++;
             } else {
             } else {

+ 12 - 9
RemoteIDModule/mavlink.cpp

@@ -134,7 +134,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
         dev_printf("Got OPEN_DRONE_ID_SYSTEM\n");
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
         packets_received_mask |= PKT_SYSTEM;
         packets_received_mask |= PKT_SYSTEM;
-        last_system_msg_ms = now_ms;
+        last_system_ms = now_ms;
         break;
         break;
     }
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: {
@@ -153,17 +153,21 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
 void MAVLinkSerial::arm_status_send(void)
 void MAVLinkSerial::arm_status_send(void)
 {
 {
     const uint32_t max_age_location_ms = 3000;
     const uint32_t max_age_location_ms = 3000;
-    const uint32_t max_age_other_ms = 2200;
+    const uint32_t max_age_other_ms = 22000;
     const uint32_t now_ms = millis();
     const uint32_t now_ms = millis();
     const char *reason = "";
     const char *reason = "";
     uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
     uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
 
 
-    if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms ||
-        last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms ||
-        last_self_id_ms == 0  || now_ms - last_self_id_ms > max_age_other_ms ||
-        last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms ||
-        last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
-        reason = "missing ODID messages";
+    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) {
     } else if (location.latitude == 0 && location.longitude == 0) {
         reason = "Bad location";
         reason = "Bad location";
     } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
     } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
@@ -194,7 +198,6 @@ bool MAVLinkSerial::system_valid(void)
     if (last_system_ms == 0 ||
     if (last_system_ms == 0 ||
         last_self_id_ms == 0 ||
         last_self_id_ms == 0 ||
         last_basic_id_ms == 0 ||
         last_basic_id_ms == 0 ||
-        last_system_ms == 0 ||
         last_operator_id_ms == 0) {
         last_operator_id_ms == 0) {
         return false;
         return false;
     }
     }

+ 0 - 2
RemoteIDModule/mavlink.h

@@ -97,7 +97,5 @@ private:
     mavlink_open_drone_id_system_t system;
     mavlink_open_drone_id_system_t system;
     mavlink_open_drone_id_operator_id_t operator_id;
     mavlink_open_drone_id_operator_id_t operator_id;
 
 
-    uint32_t last_system_msg_ms;
-
     uint32_t packets_received_mask;
     uint32_t packets_received_mask;
 };
 };