Skip to content

Commit

Permalink
gps(resilience): reimplement resilience using official new message
Browse files Browse the repository at this point in the history
Use the official new MAVLink message for the implementation of
resilience.

wip
  • Loading branch information
flyingthingsintothings committed Jun 21, 2024
1 parent 4a09fbf commit 68a91da
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 12 deletions.
2 changes: 1 addition & 1 deletion libs/mavlink/include/mavlink/v2.0
Submodule v2.0 updated 62 files
+2 −2 ASLUAV/ASLUAV.h
+1 −1 ASLUAV/mavlink.h
+1 −1 ASLUAV/version.h
+1 −1 AVSSUAS/AVSSUAS.h
+1 −1 AVSSUAS/mavlink.h
+1 −1 AVSSUAS/version.h
+4 −4 all/all.h
+1 −1 all/mavlink.h
+1 −1 all/version.h
+2 −2 ardupilotmega/ardupilotmega.h
+1 −1 ardupilotmega/mavlink.h
+1 −1 ardupilotmega/version.h
+4 −4 common/common.h
+1 −1 common/mavlink.h
+1 −1 common/version.h
+1 −1 csAirLink/csAirLink.h
+1 −1 csAirLink/mavlink.h
+1 −1 csAirLink/version.h
+1 −1 cubepilot/cubepilot.h
+1 −1 cubepilot/mavlink.h
+1 −1 cubepilot/version.h
+88 −5 development/development.h
+1 −1 development/mavlink.h
+6 −6 development/mavlink_msg_battery_status_v2.h
+456 −0 development/mavlink_msg_fuel_status.h
+568 −0 development/mavlink_msg_gnss_integrity.h
+138 −0 development/testsuite.h
+1 −1 development/version.h
+1 −1 icarous/icarous.h
+1 −1 icarous/mavlink.h
+1 −1 icarous/version.h
+2 −2 matrixpilot/matrixpilot.h
+1 −1 matrixpilot/mavlink.h
+1 −1 matrixpilot/version.h
+2 −2 message_definitions/all.xml
+8 −7 message_definitions/common.xml
+140 −2 message_definitions/development.xml
+1 −1 message_definitions/matrixpilot.xml
+1 −1 minimal/mavlink.h
+1 −1 minimal/minimal.h
+1 −1 minimal/version.h
+1 −1 paparazzi/mavlink.h
+1 −1 paparazzi/paparazzi.h
+1 −1 paparazzi/version.h
+1 −1 python_array_test/mavlink.h
+1 −1 python_array_test/python_array_test.h
+1 −1 python_array_test/version.h
+1 −1 standard/mavlink.h
+1 −1 standard/standard.h
+1 −1 standard/version.h
+1 −1 storm32/mavlink.h
+2 −2 storm32/storm32.h
+1 −1 storm32/version.h
+1 −1 test/mavlink.h
+1 −1 test/test.h
+1 −1 test/version.h
+1 −1 uAvionix/mavlink.h
+1 −1 uAvionix/uAvionix.h
+1 −1 uAvionix/version.h
+1 −1 ualberta/mavlink.h
+1 −1 ualberta/ualberta.h
+1 −1 ualberta/version.h
6 changes: 1 addition & 5 deletions src/Comms/MockLink/MockLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1323,11 +1323,7 @@ void MockLink::_sendGpsRawInt(void)
0, // Altitude uncertainty in meters * 1000 (positive for up).
0, // Speed uncertainty in meters * 1000 (positive for up).
0, // Heading / track uncertainty in degrees * 1e5.
65535, // Yaw not provided
0, // No system errors
0, // No authentication info provided
0, // No jamming info provided
0); // No spoofing info provided
65535);
respondWithMavlinkMessage(msg);
}

Expand Down
17 changes: 14 additions & 3 deletions src/Vehicle/FactGroups/VehicleGPSFactGroup.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include "VehicleGPSFactGroup.h"
#include "Vehicle.h"
#include "QGCGeo.h"
#include "development/mavlink_msg_gnss_integrity.h"

VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
Expand Down Expand Up @@ -57,6 +58,9 @@ void VehicleGPSFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_
case MAVLINK_MSG_ID_HIGH_LATENCY2:
_handleHighLatency2(message);
break;
case MAVLINK_MSG_ID_GNSS_INTEGRITY:
_handleGnssIntegrity(message);
break;
default:
break;
}
Expand All @@ -75,9 +79,6 @@ void VehicleGPSFactGroup::_handleGpsRawInt(mavlink_message_t& message)
vdop()->setRawValue (gpsRawInt.epv == UINT16_MAX ? qQNaN() : gpsRawInt.epv / 100.0);
courseOverGround()->setRawValue (gpsRawInt.cog == UINT16_MAX ? qQNaN() : gpsRawInt.cog / 100.0);
lock()->setRawValue (gpsRawInt.fix_type);
systemErrors()->setRawValue (gpsRawInt.system_errors);
spoofingState()->setRawValue (gpsRawInt.spoofing_state);
authenticationState()->setRawValue (gpsRawInt.authentication_state);
}

void VehicleGPSFactGroup::_handleHighLatency(mavlink_message_t& message)
Expand Down Expand Up @@ -113,3 +114,13 @@ void VehicleGPSFactGroup::_handleHighLatency2(mavlink_message_t& message)
hdop()->setRawValue (highLatency2.eph == UINT8_MAX ? qQNaN() : highLatency2.eph / 10.0);
vdop()->setRawValue (highLatency2.epv == UINT8_MAX ? qQNaN() : highLatency2.epv / 10.0);
}

void VehicleGPSFactGroup::_handleGnssIntegrity(mavlink_message_t& message)
{
mavlink_gnss_integrity_t gnssIntegrity;
mavlink_msg_gnss_integrity_decode(&message, &gnssIntegrity);

systemErrors()->setRawValue (gnssIntegrity.system_errors);
spoofingState()->setRawValue (gnssIntegrity.spoofing_state);
authenticationState()->setRawValue(gnssIntegrity.authentication_state);
}
7 changes: 4 additions & 3 deletions src/Vehicle/FactGroups/VehicleGPSFactGroup.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,10 @@ class VehicleGPSFactGroup : public FactGroup
virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override;

protected:
void _handleGpsRawInt (mavlink_message_t& message);
void _handleHighLatency (mavlink_message_t& message);
void _handleHighLatency2(mavlink_message_t& message);
void _handleGpsRawInt (mavlink_message_t& message);
void _handleHighLatency (mavlink_message_t& message);
void _handleHighLatency2 (mavlink_message_t& message);
void _handleGnssIntegrity(mavlink_message_t& message);

const QString _latFactName = QStringLiteral("lat");
const QString _lonFactName = QStringLiteral("lon");
Expand Down

0 comments on commit 68a91da

Please sign in to comment.