mirror of
https://github.com/opentx/opentx.git
synced 2025-07-15 12:25:12 +03:00
[Crossfire] Telemetry new fields (GPS / Battery)
I did a refactoring for the latitude and longitude decoding which should be tested carefully for FrSky S.PORT and D telemetry There was a double conversion in S.PORT protocol, there are less maths now, and perhaps precision will be better
This commit is contained in:
parent
34444aedb2
commit
26e156f9ad
23 changed files with 243 additions and 198 deletions
|
@ -147,15 +147,11 @@ static int luaGetDateTime(lua_State *L)
|
|||
static void luaPushLatLon(TelemetrySensor & telemetrySensor, TelemetryItem & telemetryItem)
|
||||
/* result is lua table containing members ["lat"] and ["lon"] as lua_Number (doubles) in decimal degrees */
|
||||
{
|
||||
uint32_t gpsLat = 0;
|
||||
uint32_t gpsLon = 0;
|
||||
telemetryItem.gps.extractLatitudeLongitude(&gpsLat, &gpsLon); /* close, but not the format we want */
|
||||
|
||||
lua_createtable(L, 0, 4);
|
||||
lua_pushtablenumber(L, "lat", gpsLat / ((telemetryItem.gps.latitudeNS == 'S') ? -1000000.0 : 1000000.0));
|
||||
lua_pushtablenumber(L, "pilot-lat", telemetryItem.pilotLatitude / ((telemetryItem.gps.latitudeNS == 'S') ? -1000000.0 : 1000000.0));
|
||||
lua_pushtablenumber(L, "lon", gpsLon / ((telemetryItem.gps.longitudeEW == 'W') ? -1000000.0 : 1000000.0));
|
||||
lua_pushtablenumber(L, "pilot-lon", telemetryItem.pilotLongitude / ((telemetryItem.gps.longitudeEW == 'W') ? -1000000.0 : 1000000.0));
|
||||
lua_pushtablenumber(L, "lat", telemetryItem.gps.latitude / 1000000.0);
|
||||
lua_pushtablenumber(L, "pilot-lat", telemetryItem.pilotLatitude / 1000000.0);
|
||||
lua_pushtablenumber(L, "lon", telemetryItem.gps.longitude / 1000000.0);
|
||||
lua_pushtablenumber(L, "pilot-lon", telemetryItem.pilotLongitude / 1000000.0);
|
||||
}
|
||||
|
||||
static void luaPushTelemetryDateTime(TelemetrySensor & telemetrySensor, TelemetryItem & telemetryItem)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue