mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: pass correct WGS84 height on GPS peripherals
This commit is contained in:
parent
cdf8cad801
commit
cc2589777f
|
@ -1859,8 +1859,12 @@ void AP_Periph_FW::can_gps_update(void)
|
|||
}
|
||||
pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL;
|
||||
pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL;
|
||||
pkt.height_ellipsoid_mm = loc.alt * 10;
|
||||
pkt.height_msl_mm = loc.alt * 10;
|
||||
pkt.height_ellipsoid_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++) {
|
||||
// the canard dsdl compiler doesn't understand float16
|
||||
pkt.ned_velocity[i] = vel[i];
|
||||
|
|
Loading…
Reference in New Issue