AP_InertialSensor: move from HAL_NO_GCS to HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2021-09-17 23:06:16 +10:00 committed by Peter Barker
parent df3cfe12a9
commit dac4134533
2 changed files with 4 additions and 0 deletions

View File

@ -2101,6 +2101,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
*/
#if HAL_GCS_ENABLED
MAV_RESULT AP_InertialSensor::simple_accel_cal()
{
uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
@ -2260,6 +2261,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
return result;
}
#endif
/*
see if gyro calibration should be performed

View File

@ -327,7 +327,9 @@ public:
void acal_update();
// simple accel calibration
#if HAL_GCS_ENABLED
MAV_RESULT simple_accel_cal();
#endif
bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }