Skip to content

Commit

Permalink
AP_Baro: fixed link with clang for shared library
Browse files Browse the repository at this point in the history
avoid unused symbols
  • Loading branch information
tridge committed Jul 6, 2024
1 parent 484af4d commit 0bda36e
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 6 deletions.
2 changes: 2 additions & 0 deletions libraries/AP_Baro/AP_Baro.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,8 +118,10 @@ class AP_Baro
// EAS2TAS for SITL
static float get_EAS2TAS_for_alt_amsl(float alt_amsl);

#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED
// lookup expected pressure for a given altitude. Used for SITL backend
static void get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K);
#endif

// lookup expected temperature in degrees C for a given altitude. Used for SITL backend
static float get_temperatureC_for_alt_amsl(const float alt_amsl);
Expand Down
8 changes: 2 additions & 6 deletions libraries/AP_Baro/AP_Baro_atmosphere.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,6 @@ T0_slope = -6.5E-3 (K/m')
The tables list altitudes -5 km to 0 km using the same equations as 0 km to 11 km.
*/

#ifndef AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED
// default to using the extended functions when doing double precision EKF (which implies more flash space and faster MCU)
// this allows for using the simple model with the --ekf-single configure option
#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE
#endif

/*
return altitude difference in meters between current pressure and a
given base_pressure in Pascal. This is a simple atmospheric model
Expand Down Expand Up @@ -314,6 +308,7 @@ float AP_Baro::_get_EAS2TAS(void) const
#endif
}

#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED
// lookup expected temperature in degrees C for a given altitude. Used for SITL backend
float AP_Baro::get_temperatureC_for_alt_amsl(const float alt_amsl)
{
Expand All @@ -329,6 +324,7 @@ float AP_Baro::get_pressure_for_alt_amsl(const float alt_amsl)
get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K);
return pressure;
}
#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED

/*
return sea level pressure given a current altitude and pressure reading
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Baro/AP_Baro_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,3 +97,9 @@
#ifndef AP_BARO_PROBE_EXT_PARAMETER_ENABLED
#define AP_BARO_PROBE_EXT_PARAMETER_ENABLED AP_BARO_PROBE_EXTERNAL_I2C_BUSES || AP_BARO_MSP_ENABLED
#endif

#ifndef AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED
// default to using the extended functions when doing double precision EKF (which implies more flash space and faster MCU)
// this allows for using the simple model with the --ekf-single configure option
#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE
#endif

0 comments on commit 0bda36e

Please sign in to comment.