mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Compass: take responsibility for not running cal if armed
This commit is contained in:
parent
f054301ec2
commit
0e8722181f
@ -123,7 +123,7 @@ public:
|
||||
const Vector3f &get_field(void) const { return get_field(get_primary()); }
|
||||
|
||||
// compass calibrator interface
|
||||
void compass_cal_update();
|
||||
void cal_update();
|
||||
|
||||
// per-motor calibration access
|
||||
void per_motor_calibration_start(void) {
|
||||
|
@ -7,8 +7,12 @@
|
||||
extern AP_HAL::HAL& hal;
|
||||
|
||||
void
|
||||
Compass::compass_cal_update()
|
||||
Compass::cal_update()
|
||||
{
|
||||
if (hal.util->get_soft_armed()) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool running = false;
|
||||
|
||||
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
||||
|
Loading…
Reference in New Issue
Block a user