mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
INS: add calibrating method
This commit is contained in:
parent
3e45052a75
commit
f9c6e35d19
@ -237,7 +237,8 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
_gyro(),
|
||||
_board_orientation(ROTATION_NONE),
|
||||
_hil_mode(false),
|
||||
_have_3D_calibration(false)
|
||||
_have_3D_calibration(false),
|
||||
_calibrating(false)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
for (uint8_t i=0; i<INS_MAX_BACKENDS; i++) {
|
||||
@ -614,6 +615,9 @@ AP_InertialSensor::_init_accel()
|
||||
|
||||
hal.console->print_P(PSTR("Init Accel"));
|
||||
|
||||
// record we are calibrating
|
||||
_calibrating = true;
|
||||
|
||||
// flash leds to tell user to keep the IMU still
|
||||
AP_Notify::flags.initialising = true;
|
||||
|
||||
@ -689,6 +693,9 @@ AP_InertialSensor::_init_accel()
|
||||
_accel_offset[k] = accel_offset[k];
|
||||
}
|
||||
|
||||
// record calibration complete
|
||||
_calibrating = false;
|
||||
|
||||
// stop flashing the leds
|
||||
AP_Notify::flags.initialising = false;
|
||||
|
||||
@ -707,6 +714,9 @@ AP_InertialSensor::_init_gyro()
|
||||
// cold start
|
||||
hal.console->print_P(PSTR("Init Gyro"));
|
||||
|
||||
// record we are calibrating
|
||||
_calibrating = true;
|
||||
|
||||
// flash leds to tell user to keep the IMU still
|
||||
AP_Notify::flags.initialising = true;
|
||||
|
||||
@ -790,9 +800,6 @@ AP_InertialSensor::_init_gyro()
|
||||
}
|
||||
}
|
||||
|
||||
// stop flashing leds
|
||||
AP_Notify::flags.initialising = false;
|
||||
|
||||
// we've kept the user waiting long enough - use the best pair we
|
||||
// found so far
|
||||
hal.console->println();
|
||||
@ -807,6 +814,12 @@ AP_InertialSensor::_init_gyro()
|
||||
_gyro_cal_ok[k] = true;
|
||||
}
|
||||
}
|
||||
|
||||
// record calibration complete
|
||||
_calibrating = false;
|
||||
|
||||
// stop flashing leds
|
||||
AP_Notify::flags.initialising = false;
|
||||
}
|
||||
|
||||
#if !defined( __AVR_ATmega1280__ )
|
||||
|
@ -97,6 +97,9 @@ public:
|
||||
///
|
||||
bool calibrated() const;
|
||||
|
||||
/// calibrating - returns true if the gyros or accels are currently being calibrated
|
||||
bool calibrating() const { return _calibrating; }
|
||||
|
||||
/// Perform cold-start initialisation for just the gyros.
|
||||
///
|
||||
/// @note This should not be called unless ::init has previously
|
||||
@ -270,6 +273,9 @@ private:
|
||||
// do we have offsets/scaling from a 3D calibration?
|
||||
bool _have_3D_calibration:1;
|
||||
|
||||
// are gyros or accels currently being calibrated
|
||||
bool _calibrating:1;
|
||||
|
||||
// the delta time in seconds for the last sample
|
||||
float _delta_time;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user