From c8680e94146056ccb25f1b9bfc229aba5d44e36f Mon Sep 17 00:00:00 2001 From: PatrickRung Date: Mon, 4 Nov 2024 22:42:48 -0800 Subject: [PATCH] Fixed issue with _lastGPS not having a altitude value in ArduPilotProtocol.cpp. --- src/ardupilot/ArduPilotProtocol.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/ardupilot/ArduPilotProtocol.cpp b/src/ardupilot/ArduPilotProtocol.cpp index b8108b4b..0fb036e1 100644 --- a/src/ardupilot/ArduPilotProtocol.cpp +++ b/src/ardupilot/ArduPilotProtocol.cpp @@ -57,15 +57,17 @@ void ArduPilotProtocol::clientDisconnected() { bool ArduPilotProtocol::validateGPSRequest(const json& j) { return util::validateKey(j, "lat", val_t::number_float) && - util::validateKey(j, "lon", val_t::number_float); + util::validateKey(j, "lon", val_t::number_float) && + util::validateKey(j, "alt", val_t::number_float); } void ArduPilotProtocol::handleGPSRequest(const json& j) { double lat = j["lat"]; double lon = j["lon"]; + double alt = j["alt"]; { std::lock_guard lock(_lastGPSMutex); - _lastGPS = gpscoords_t{lat, lon}; + _lastGPS = gpscoords_t{lat, lon, alt}; } }