Skip to content

AP_GPS: log altitude above ellipsoid instead of undulation #29904

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Apr 29, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 5 additions & 2 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1912,11 +1912,14 @@ void AP_GPS::Write_GPS(uint8_t i)

/* write auxiliary accuracy information as well */
float hacc = 0, vacc = 0, sacc = 0;
int32_t alt_ellipsoid = INT32_MIN;
float undulation = 0;
horizontal_accuracy(i, hacc);
vertical_accuracy(i, vacc);
speed_accuracy(i, sacc);
get_undulation(i, undulation);
if (get_undulation(i, undulation)) {
alt_ellipsoid = loc.alt - (undulation*100);
}
struct log_GPA pkt2{
LOG_PACKET_HEADER_INIT(LOG_GPA_MSG),
time_us : time_us,
Expand All @@ -1929,7 +1932,7 @@ void AP_GPS::Write_GPS(uint8_t i)
have_vv : (uint8_t)have_vertical_velocity(i),
sample_ms : last_message_time_ms(i),
delta_ms : last_message_delta_time_ms(i),
undulation : undulation,
alt_ellipsoid : alt_ellipsoid,
rtcm_fragments_used: rtcm_stats.fragments_used,
rtcm_fragments_discarded: rtcm_stats.fragments_discarded
};
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_GPS/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ struct PACKED log_GPS {
// @Field: VV: true if vertical velocity is available
// @Field: SMS: time since system startup this sample was taken
// @Field: Delta: system time delta between the last two reported positions
// @Field: Und: Undulation
// @Field: AEl: altitude above WGS-84 ellipsoid; INT32_MIN (-2147483648) if unknown
// @Field: RTCMFU: RTCM fragments used
// @Field: RTCMFD: RTCM fragments discarded
struct PACKED log_GPA {
Expand All @@ -78,7 +78,7 @@ struct PACKED log_GPA {
uint8_t have_vv;
uint32_t sample_ms;
uint16_t delta_ms;
float undulation;
int32_t alt_ellipsoid;
uint16_t rtcm_fragments_used;
uint16_t rtcm_fragments_discarded;
};
Expand Down Expand Up @@ -207,7 +207,7 @@ struct PACKED log_GPS_RAWS {
{ LOG_GPS_MSG, sizeof(log_GPS), \
"GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#-s-S-DUmnhnh-", "F--C-0BGGB000--" , true }, \
{ LOG_GPA_MSG, sizeof(log_GPA), \
"GPA", "QBCCCCfBIHfHH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta,Und,RTCMFU,RTCMFD", "s#-mmnd-ssm--", "F-BBBB0-CC0--" , true }, \
"GPA", "QBCCCCfBIHeHH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta,AEl,RTCMFU,RTCMFD", "s#-mmnd-ssm--", "F-BBBB0-CCB--" , true }, \
{ LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \
"UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s#-----", "F------" , true }, \
{ LOG_GPS_UBX2_MSG, sizeof(log_Ubx2), \
Expand Down
Loading