mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
AP_Periph: fixed undulation in Fix2 pkt
This commit is contained in:
parent
8b0cfe4904
commit
c6fae0425b
@ -1939,6 +1939,10 @@ void AP_Periph_FW::can_gps_update(void)
|
|||||||
pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL;
|
pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL;
|
||||||
pkt.height_ellipsoid_mm = loc.alt * 10;
|
pkt.height_ellipsoid_mm = loc.alt * 10;
|
||||||
pkt.height_msl_mm = loc.alt * 10;
|
pkt.height_msl_mm = loc.alt * 10;
|
||||||
|
float undulation;
|
||||||
|
if (gps.get_undulation(undulation)) {
|
||||||
|
pkt.height_ellipsoid_mm -= undulation*1000;
|
||||||
|
}
|
||||||
for (uint8_t i=0; i<3; i++) {
|
for (uint8_t i=0; i<3; i++) {
|
||||||
pkt.ned_velocity[i] = vel[i];
|
pkt.ned_velocity[i] = vel[i];
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user