AP_Baro: log AltAMSL

useful as GPS comparison
This commit is contained in:
Andrew Tridgell 2024-05-07 07:47:39 +10:00 committed by Peter Barker
parent f8ce6a8623
commit 3d2037ef03
3 changed files with 9 additions and 5 deletions

View File

@ -102,7 +102,8 @@ public:
float get_altitude(uint8_t instance) const { return sensors[instance].altitude; } float get_altitude(uint8_t instance) const { return sensors[instance].altitude; }
// get altitude above mean sea level // get altitude above mean sea level
float get_altitude_AMSL(void) const { return get_altitude() + _field_elevation_active; } float get_altitude_AMSL(uint8_t instance) const { return get_altitude(instance) + _field_elevation_active; }
float get_altitude_AMSL(void) const { return get_altitude_AMSL(_primary); }
// returns which i2c bus is considered "the" external bus // returns which i2c bus is considered "the" external bus
uint8_t external_bus() const { return _ext_bus; } uint8_t external_bus() const { return _ext_bus; }

View File

@ -13,6 +13,7 @@ void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance)
time_us : time_us, time_us : time_us,
instance : baro_instance, instance : baro_instance,
altitude : get_altitude(baro_instance), altitude : get_altitude(baro_instance),
altitude_AMSL : get_altitude_AMSL(baro_instance),
pressure : get_pressure(baro_instance), pressure : get_pressure(baro_instance),
temperature : (int16_t)(get_temperature(baro_instance) * 100 + 0.5f), temperature : (int16_t)(get_temperature(baro_instance) * 100 + 0.5f),
climbrate : get_climb_rate(), climbrate : get_climb_rate(),

View File

@ -11,6 +11,7 @@
// @Field: TimeUS: Time since system startup // @Field: TimeUS: Time since system startup
// @Field: I: barometer sensor instance number // @Field: I: barometer sensor instance number
// @Field: Alt: calculated altitude // @Field: Alt: calculated altitude
// @Field: AltAMSL: altitude AMSL
// @Field: Press: measured atmospheric pressure // @Field: Press: measured atmospheric pressure
// @Field: Temp: measured atmospheric temperature // @Field: Temp: measured atmospheric temperature
// @Field: CRt: derived climb rate from primary barometer // @Field: CRt: derived climb rate from primary barometer
@ -23,6 +24,7 @@ struct PACKED log_BARO {
uint64_t time_us; uint64_t time_us;
uint8_t instance; uint8_t instance;
float altitude; float altitude;
float altitude_AMSL;
float pressure; float pressure;
int16_t temperature; int16_t temperature;
float climbrate; float climbrate;
@ -51,10 +53,10 @@ struct PACKED log_BARD {
#define LOG_STRUCTURE_FROM_BARO \ #define LOG_STRUCTURE_FROM_BARO \
{ LOG_BARO_MSG, sizeof(log_BARO), \ { LOG_BARO_MSG, sizeof(log_BARO), \
"BARO", \ "BARO", \
"Q" "B" "f" "f" "c" "f" "I" "f" "f" "B", \ "Q" "B" "f" "f" "f" "c" "f" "I" "f" "f" "B", \
"TimeUS," "I," "Alt," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \ "TimeUS," "I," "Alt," "AltAMSL," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \
"s" "#" "m" "P" "O" "n" "s" "m" "O" "-", \ "s" "#" "m" "m" "P" "O" "n" "s" "m" "O" "-", \
"F" "-" "0" "0" "B" "0" "C" "?" "0" "-", \ "F" "-" "0" "0" "0" "B" "0" "C" "?" "0" "-", \
true \ true \
}, \ }, \
{ LOG_BARD_MSG, sizeof(log_BARD), \ { LOG_BARD_MSG, sizeof(log_BARD), \