Browse Source

AP_AHRS: added send_ekf_status_report()

master
Andrew Tridgell 9 years ago
parent
commit
232fc8a64d
  1. 13
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  2. 3
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

13
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -709,5 +709,18 @@ bool AP_AHRS_NavEKF::resetHeightDatum(void) @@ -709,5 +709,18 @@ bool AP_AHRS_NavEKF::resetHeightDatum(void)
return false;
}
// send a EKF_STATUS_REPORT for current EKF
void AP_AHRS_NavEKF::send_ekf_status_report(mavlink_channel_t chan)
{
switch (active_EKF_type()) {
case EKF_TYPE1:
default:
return EKF1.send_status_report(chan);
case EKF_TYPE2:
return EKF2.send_status_report(chan);
}
}
#endif // AP_AHRS_NAVEKF_AVAILABLE

3
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -152,6 +152,9 @@ public: @@ -152,6 +152,9 @@ public:
// Returns true if the height datum reset has been performed
// If using a range finder for height no reset is performed and it returns false
bool resetHeightDatum(void);
// send a EKF_STATUS_REPORT for current EKF
void send_ekf_status_report(mavlink_channel_t chan);
private:
enum EKF_TYPE {EKF_TYPE_NONE, EKF_TYPE1, EKF_TYPE2};

Loading…
Cancel
Save