AP_AHRS: make posOffset a const reference
This commit is contained in:
parent
703ef0ca0e
commit
772209b3f3
@ -1038,7 +1038,7 @@ bool AP_AHRS_NavEKF::get_filter_status(nav_filter_status &status) const
|
||||
}
|
||||
|
||||
// write optical flow data to EKF
|
||||
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, Vector3f &posOffset)
|
||||
void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
|
||||
{
|
||||
EKF1.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
||||
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
||||
|
@ -155,7 +155,7 @@ public:
|
||||
bool get_vert_pos_rate(float &velocity);
|
||||
|
||||
// write optical flow measurements to EKF
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, Vector3f &posOffset);
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset);
|
||||
|
||||
// inibit GPS usage
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
Loading…
Reference in New Issue
Block a user