Browse Source

check timestamp of system and location messages

Roel Schiphorst 3 years ago
parent
commit
2185e33055

+ 11 - 2
RemoteIDModule/DroneCAN.cpp

@@ -493,7 +493,12 @@ void DroneCAN::handle_System(CanardRxTransfer* transfer)
     dronecan_remoteid_System pkt {};
     auto &mpkt = system;
     dronecan_remoteid_System_decode(transfer, &pkt);
-    last_system_ms = millis();
+
+    if ((last_system_timestamp != pkt.timestamp) || (pkt.timestamp == 0)) {
+        //only update the timestamp if we receive information with a different timestamp
+        last_system_ms = millis();
+        last_system_timestamp = pkt.timestamp;
+	}
     memset(&mpkt, 0, sizeof(mpkt));
 
     COPY_STR(id_or_mac);
@@ -529,7 +534,11 @@ void DroneCAN::handle_Location(CanardRxTransfer* transfer)
     dronecan_remoteid_Location pkt {};
     auto &mpkt = location;
     dronecan_remoteid_Location_decode(transfer, &pkt);
-    last_location_ms = millis();
+    if (last_location_timestamp != pkt.timestamp) {
+        //only update the timestamp if we receive information with a different timestamp
+        last_location_ms = millis();
+        last_location_timestamp = pkt.timestamp;
+    }
     memset(&mpkt, 0, sizeof(mpkt));
 
     COPY_STR(id_or_mac);

+ 15 - 1
RemoteIDModule/mavlink.cpp

@@ -144,6 +144,11 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION: {
         mavlink_msg_open_drone_id_location_decode(&msg, &location);
+        if (last_location_timestamp != location.timestamp) {
+            //only update the timestamp if we receive information with a different timestamp
+            last_location_ms = millis();
+            last_location_timestamp = location.timestamp;
+        }
         last_location_ms = now_ms;
         break;
     }
@@ -163,7 +168,11 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: {
         mavlink_msg_open_drone_id_system_decode(&msg, &system);
-        last_system_ms = now_ms;
+        if ((last_system_timestamp != system.timestamp) || (system.timestamp == 0)) {
+            //only update the timestamp if we receive information with a different timestamp
+            last_system_ms = millis();
+            last_system_timestamp = system.timestamp;
+        }
         break;
     }
     case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: {
@@ -176,6 +185,11 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
         if (last_system_ms != 0) {
             // we can only mark system as updated if we have the other
             // information already
+            if ((last_system_timestamp != system.timestamp) || (pkt_system_update.timestamp == 0)) {
+                //only update the timestamp if we receive information with a different timestamp
+                last_system_ms = millis();
+                last_system_timestamp = pkt_system_update.timestamp;
+            }
             last_system_ms = now_ms;
         }
         break;

+ 2 - 0
RemoteIDModule/transport.cpp

@@ -14,6 +14,8 @@ 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;
+uint32_t Transport::last_system_timestamp;
+float Transport::last_location_timestamp;
 
 mavlink_open_drone_id_location_t Transport::location;
 mavlink_open_drone_id_basic_id_t Transport::basic_id;

+ 2 - 0
RemoteIDModule/transport.h

@@ -65,6 +65,8 @@ protected:
     static uint32_t last_self_id_ms;
     static uint32_t last_operator_id_ms;
     static uint32_t last_system_ms;
+    static uint32_t last_system_timestamp;
+    static float last_location_timestamp;
 
     static mavlink_open_drone_id_location_t location;
     static mavlink_open_drone_id_basic_id_t basic_id;