mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
AP_AHRS: Allow EKF to pull data from range finder object
This commit is contained in:
parent
32f87d008a
commit
7f1749dc1c
@ -359,9 +359,9 @@ bool AP_AHRS_NavEKF::initialised(void) 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, uint8_t &rangeHealth, float &rawSonarRange)
|
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas)
|
||||||
{
|
{
|
||||||
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, rangeHealth, rawSonarRange);
|
EKF.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas);
|
||||||
}
|
}
|
||||||
|
|
||||||
// inhibit GPS useage
|
// inhibit GPS useage
|
||||||
|
@ -34,9 +34,9 @@ class AP_AHRS_NavEKF : public AP_AHRS_DCM
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps) :
|
AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gps, RangeFinder &rng) :
|
||||||
AP_AHRS_DCM(ins, baro, gps),
|
AP_AHRS_DCM(ins, baro, gps),
|
||||||
EKF(this, baro),
|
EKF(this, baro, rng),
|
||||||
ekf_started(false),
|
ekf_started(false),
|
||||||
startup_delay_ms(1000),
|
startup_delay_ms(1000),
|
||||||
start_time_ms(0)
|
start_time_ms(0)
|
||||||
@ -104,7 +104,7 @@ public:
|
|||||||
bool get_relative_position_NED(Vector3f &vec) const;
|
bool get_relative_position_NED(Vector3f &vec) const;
|
||||||
|
|
||||||
// write optical flow measurements to EKF
|
// write optical flow measurements to EKF
|
||||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, uint8_t &rangeHealth, float &rawSonarRange);
|
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas);
|
||||||
|
|
||||||
// inibit GPS useage
|
// inibit GPS useage
|
||||||
uint8_t setInhibitGPS(void);
|
uint8_t setInhibitGPS(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user