mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2025-12-10 00:28:42 -06:00
AP_TempCalibration: add HAL_TCAL_BARO_EXP_DEFAULT
This commit is contained in:
parent
23c21bfcec
commit
e7166c42ec
@ -34,6 +34,10 @@ extern const AP_HAL::HAL& hal;
|
||||
# define debug(fmt, args ...)
|
||||
#endif
|
||||
|
||||
#ifndef HAL_TCAL_BARO_EXP_DEFAULT
|
||||
#define HAL_TCAL_BARO_EXP_DEFAULT 0.0f
|
||||
#endif
|
||||
|
||||
// table of user settable and learned parameters
|
||||
const AP_Param::GroupInfo AP_TempCalibration::var_info[] = {
|
||||
|
||||
@ -70,7 +74,7 @@ const AP_Param::GroupInfo AP_TempCalibration::var_info[] = {
|
||||
// @ReadOnly: True
|
||||
// @Volatile: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_BARO_EXP", 5, AP_TempCalibration, baro_exponent, 0),
|
||||
AP_GROUPINFO("_BARO_EXP", 5, AP_TempCalibration, baro_exponent, HAL_TCAL_BARO_EXP_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user