mirror of https://github.com/ArduPilot/ardupilot
AP_TempCalibration: add and use AP_TEMPCALIBRATION_ENABLED
This commit is contained in:
parent
336c16cae0
commit
3411b85b71
|
@ -16,6 +16,10 @@
|
||||||
temperature calibration library
|
temperature calibration library
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "AP_TempCalibration_config.h"
|
||||||
|
|
||||||
|
#if AP_TEMPCALIBRATION_ENABLED
|
||||||
|
|
||||||
#include "AP_TempCalibration.h"
|
#include "AP_TempCalibration.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
|
@ -231,3 +235,5 @@ void AP_TempCalibration::update(void)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_TEMPCALIBRATION_ENABLED
|
||||||
|
|
|
@ -18,6 +18,10 @@
|
||||||
and opportunistically calibrates sensors when the vehicle is still
|
and opportunistically calibrates sensors when the vehicle is still
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "AP_TempCalibration_config.h"
|
||||||
|
|
||||||
|
#if AP_TEMPCALIBRATION_ENABLED
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
|
@ -79,3 +83,5 @@ private:
|
||||||
float calculate_p_range(float baro_factor) const;
|
float calculate_p_range(float baro_factor) const;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif // AP_TEMPCALIBRATION_ENABLED
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
||||||
|
#ifndef AP_TEMPCALIBRATION_ENABLED
|
||||||
|
#define AP_TEMPCALIBRATION_ENABLED 1
|
||||||
|
#endif
|
Loading…
Reference in New Issue