Skip to content

Commit

Permalink
AP_Baro: disable BARO_FIELD_ELV for sub
Browse files Browse the repository at this point in the history
  • Loading branch information
clydemcqueen committed Apr 2, 2024
1 parent bc29550 commit 34baab1
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions libraries/AP_Baro/AP_Baro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@
#define HAL_BARO_ALLOW_INIT_NO_BARO
#endif

#ifndef AP_FIELD_ELEVATION_ENABLED
#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub)
#endif

extern const AP_HAL::HAL& hal;

// table of user settable parameters
Expand Down Expand Up @@ -219,7 +223,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
// @Path: AP_Baro_Wind.cpp
AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff),
#endif
#ifndef HAL_BUILD_AP_PERIPH
#if AP_FIELD_ELEVATION_ENABLED
// @Param: _FIELD_ELV
// @DisplayName: field elevation
// @Description: User provided field elevation in meters. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level.
Expand Down Expand Up @@ -958,7 +962,7 @@ void AP_Baro::update(void)
}
}
}
#ifndef HAL_BUILD_AP_PERIPH
#if AP_FIELD_ELEVATION_ENABLED
update_field_elevation();
#endif

Expand Down

0 comments on commit 34baab1

Please sign in to comment.