AP_InertialSensor: use ahrs singleton for simple accelcal

This commit is contained in:
Peter Barker 2018-03-17 23:03:13 +11:00 committed by Francisco Ferreira
parent 030a1997f5
commit 2396a248ed
2 changed files with 5 additions and 5 deletions

View File

@ -1846,7 +1846,7 @@ bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vec
/*
perform a simple 1D accel calibration, returning mavlink result code
*/
MAV_RESULT AP_InertialSensor::simple_accel_cal(AP_AHRS &ahrs)
MAV_RESULT AP_InertialSensor::simple_accel_cal()
{
uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
Vector3f last_average[INS_MAX_INSTANCES];
@ -1974,7 +1974,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal(AP_AHRS &ahrs)
}
// force trim to zero
ahrs.set_trim(Vector3f(0, 0, 0));
AP::ahrs().set_trim(Vector3f(0, 0, 0));
} else {
hal.console->printf("\nFAILED\n");
// restore old values
@ -1996,7 +1996,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal(AP_AHRS &ahrs)
}
// and reset state estimators
ahrs.reset();
AP::ahrs().reset();
// stop flashing leds
AP_Notify::flags.initialising = false;

View File

@ -268,7 +268,7 @@ public:
void acal_update();
// simple accel calibration
MAV_RESULT simple_accel_cal(AP_AHRS &ahrs);
MAV_RESULT simple_accel_cal();
bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }