Browse Source

AP_AHRS: add position offset to optical flow interface

mission-4.1.18
priseborough 9 years ago committed by Andrew Tridgell
parent
commit
6069c37b19
  1. 6
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  2. 2
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

6
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -1038,10 +1038,10 @@ bool AP_AHRS_NavEKF::get_filter_status(nav_filter_status &status) const
} }
// write optical flow data to EKF // write optical flow data to EKF
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas) void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, Vector3f &posOffset)
{ {
EKF1.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas); EKF1.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas); EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
} }
// inhibit GPS usage // inhibit GPS usage

2
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -155,7 +155,7 @@ public:
bool get_vert_pos_rate(float &velocity); bool get_vert_pos_rate(float &velocity);
// write optical flow measurements to EKF // write optical flow measurements to EKF
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas); void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, Vector3f &posOffset);
// inibit GPS usage // inibit GPS usage
uint8_t setInhibitGPS(void); uint8_t setInhibitGPS(void);

Loading…
Cancel
Save