Browse Source

Copter: add compass_cal update function

master
Jonathan Challinger 10 years ago committed by Andrew Tridgell
parent
commit
7d67a00aa3
  1. 1
      ArduCopter/Copter.h
  2. 7
      ArduCopter/sensors.cpp

1
ArduCopter/Copter.h

@ -534,6 +534,7 @@ private: @@ -534,6 +534,7 @@ private:
static const struct LogStructure log_structure[];
void compass_accumulate(void);
void compass_cal_update(void);
void barometer_accumulate(void);
void perf_update(void);
void fast_loop();

7
ArduCopter/sensors.cpp

@ -174,6 +174,13 @@ void Copter::read_receiver_rssi(void) @@ -174,6 +174,13 @@ void Copter::read_receiver_rssi(void)
receiver_rssi = rssi.read_receiver_rssi_uint8();
}
void Copter::compass_cal_update()
{
if (!hal.util->get_soft_armed()) {
compass.compass_cal_update();
}
}
#if EPM_ENABLED == ENABLED
// epm update - moves epm pwm output back to neutral after grab or release is completed
void Copter::epm_update()

Loading…
Cancel
Save