AP_TempCalibration: do not take reference to ins

This commit is contained in:
Peter Barker 2018-03-16 16:31:03 +11:00 committed by Lucas De Marchi
parent 78ca188dc3
commit 622be10163
2 changed files with 9 additions and 9 deletions

View File

@ -77,11 +77,6 @@ const AP_Param::GroupInfo AP_TempCalibration::var_info[] = {
AP_GROUPEND
};
AP_TempCalibration::AP_TempCalibration(AP_InertialSensor &_ins) :
ins(_ins)
{
}
/*
calculate the correction given an exponent and a temperature
@ -178,7 +173,7 @@ void AP_TempCalibration::learn_calibration(void)
// if we have any movement then we reset learning
if (learn_values == nullptr ||
!ins.is_still()) {
!AP::ins().is_still()) {
debug("learn reset\n");
setup_learning();
if (learn_values == nullptr) {

View File

@ -26,14 +26,20 @@
class AP_TempCalibration
{
public:
// constructor
AP_TempCalibration(AP_InertialSensor &ins);
// constructor. This remains because construction of Copter's g2
// object becomes problematic if we don't have at least one object
// to initialise
AP_TempCalibration() {}
// settable parameters
static const struct AP_Param::GroupInfo var_info[];
void update(void);
/* Do not allow copies */
AP_TempCalibration(const AP_TempCalibration &other) = delete;
AP_TempCalibration &operator=(const AP_TempCalibration&) = delete;
enum {
TC_DISABLED = 0,
TC_ENABLE_USE = 1,
@ -41,7 +47,6 @@ public:
};
private:
AP_InertialSensor &ins;
AP_Int8 enabled;
AP_Int8 temp_min;