Browse Source

AP_AHRS: added prearm_failure_reason()

master
Andrew Tridgell 10 years ago
parent
commit
c18c6d894e
  1. 3
      libraries/AP_AHRS/AP_AHRS.h
  2. 10
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  3. 3
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

3
libraries/AP_AHRS/AP_AHRS.h

@ -197,6 +197,9 @@ public: @@ -197,6 +197,9 @@ public:
// Methods
virtual void update(void) = 0;
// report any reason for why the backend is refusing to initialise
virtual const char *prearm_failure_reason(void) const { return nullptr; }
// Euler angles (radians)
float roll;
float pitch;

10
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -21,6 +21,7 @@ @@ -21,6 +21,7 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_AHRS.h"
#include <AP_Vehicle/AP_Vehicle.h>
#include <GCS_MAVLink/GCS.h>
#if AP_AHRS_NAVEKF_AVAILABLE
@ -412,5 +413,14 @@ bool AP_AHRS_NavEKF::getMagOffsets(Vector3f &magOffsets) @@ -412,5 +413,14 @@ bool AP_AHRS_NavEKF::getMagOffsets(Vector3f &magOffsets)
return status;
}
// report any reason for why the backend is refusing to initialise
const char *AP_AHRS_NavEKF::prearm_failure_reason(void) const
{
if (_ekf_use != EKF_DO_NOT_USE) {
return EKF.prearm_failure_reason();
}
return nullptr;
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

3
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -124,6 +124,9 @@ AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder & @@ -124,6 +124,9 @@ AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &
// true if offsets are valid
bool getMagOffsets(Vector3f &magOffsets);
// report any reason for why the backend is refusing to initialise
const char *prearm_failure_reason(void) const override;
private:
bool using_EKF(void) const;

Loading…
Cancel
Save