Skip to content

Commit 0805156

Browse files
committed
AP_GPS: NOVA: fix undulation
Required for the ellipsoid height to be broadcast correctly over e.g. MAVLink. Tested on a NovAtel OEM719.
1 parent 1dcef76 commit 0805156

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

libraries/AP_GPS/AP_GPS_NOVA.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -211,7 +211,7 @@ AP_GPS_NOVA::process_message(void)
211211
state.location.lat = (int32_t) (bestposu.lat * (double)1e7);
212212
state.location.lng = (int32_t) (bestposu.lng * (double)1e7);
213213
state.have_undulation = true;
214-
state.undulation = bestposu.undulation;
214+
state.undulation = -bestposu.undulation;
215215
set_alt_amsl_cm(state, bestposu.hgt * 100);
216216

217217
state.num_sats = bestposu.svsused;

0 commit comments

Comments
 (0)