mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS : EKF optical flow fusion support preliminary changes
This commit is contained in:
parent
34249ffa42
commit
7b76fc29fb
|
@ -317,5 +317,10 @@ bool AP_AHRS_NavEKF::initialised(void) const
|
|||
return (ekf_started && (hal.scheduler->millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
|
||||
};
|
||||
|
||||
// write optical flow data to EKF
|
||||
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, float &rawSonarRange, uint32_t &msecFlowMeas)
|
||||
{
|
||||
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawSonarRange, msecFlowMeas);
|
||||
}
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
|
|
|
@ -101,6 +101,9 @@ public:
|
|||
bool get_velocity_NED(Vector3f &vec) const;
|
||||
bool get_relative_position_NED(Vector3f &vec) const;
|
||||
|
||||
// write optical flow measurements to EKF
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, float &rawSonarRange, uint32_t &msecFlowMeas);
|
||||
|
||||
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
|
||||
|
||||
// is the AHRS subsystem healthy?
|
||||
|
|
Loading…
Reference in New Issue