Skip to content

Commit

Permalink
Tracker: correct altitude pressure offset calculation
Browse files Browse the repository at this point in the history
the value nav_status.altitude_offset is expected to be a correction for differences between the barometers.  The user calibrates this value with a MAV_CMD_PREFLIGHT_CALIBRATION call.

Without this patch we were passing in the raw barometric pressure values for the tracker and the tracked vehicle.  It seems get_altitude_difference is expecting a sea-level pressure as its first argument now, as it subtracts the field elevation from the pressure-difference altitude calculations.

Change our call to provide a sea-level-adjusted value
  • Loading branch information
peterbarker committed Feb 3, 2024
1 parent cc8a9d1 commit 7b20e4b
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion AntennaTracker/tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
*/
void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
{
float local_pressure = barometer.get_pressure();
float local_pressure = barometer.get_sealevel_pressure(barometer.get_pressure());
float aircraft_pressure = msg.press_abs*100.0f;

// calculate altitude difference based on difference in barometric pressure
Expand All @@ -166,6 +166,7 @@ void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
nav_status.altitude_offset = -alt_diff;
nav_status.alt_difference_baro = 0;
nav_status.need_altitude_calibration = false;
gcs().send_text(MAV_SEVERITY_INFO, "Pressure alt delta=%f", alt_diff);
#if HAL_LOGGING_ENABLED
logger.Write_NamedValueFloat("NAV_ALT_OFS", nav_status.altitude_offset);
#endif
Expand Down

0 comments on commit 7b20e4b

Please sign in to comment.