AP_GPS_SBF: add accuracy estimates

This commit is contained in:
Michael Oborne 2015-09-09 09:22:41 +08:00 committed by Andrew Tridgell
parent 1103451d36
commit 88cf710f94
2 changed files with 13 additions and 0 deletions

View File

@ -218,6 +218,11 @@ AP_GPS_SBF::process_message(void)
state.ground_course_cd = (int32_t)(100 * ToDeg(atan2f(state.velocity[1], state.velocity[0])));
state.ground_course_cd = wrap_360_cd(state.ground_course_cd);
state.horizontal_accuracy = (float)temp.HAccuracy * 0.01f;
state.vertical_accuracy = (float)temp.VAccuracy * 0.01f;
state.have_horizontal_accuracy = true;
state.have_vertical_accuracy = true;
}
// Update position state (dont use 2·10^10)

View File

@ -82,6 +82,14 @@ private:
uint16_t MeanCorrAge;
uint32_t SignalInfo;
uint8_t AlertFlag;
// rev1
uint8_t NrBases;
uint16_t PPPInfo;
// rev2
uint16_t Latency;
uint16_t HAccuracy;
uint16_t VAccuracy;
uint8_t Misc;
};
struct PACKED msg4001