Skip to content

Commit

Permalink
Fixed issue with _lastGPS not having a altitude value in ArduPilotPro…
Browse files Browse the repository at this point in the history
…tocol.cpp.
  • Loading branch information
PatrickRung committed Nov 5, 2024
1 parent d365336 commit c8680e9
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions src/ardupilot/ArduPilotProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::mutex> lock(_lastGPSMutex);
_lastGPS = gpscoords_t{lat, lon};
_lastGPS = gpscoords_t{lat, lon, alt};
}
}

Expand Down

0 comments on commit c8680e9

Please sign in to comment.