mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fix writeOptFlowMeas signature
const some of the vectors, stop taking references to scalars that aren't being changed
This commit is contained in:
parent
7db5daadad
commit
306a40bb77
|
@ -1181,7 +1181,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, const Vector3f &posOffset)
|
||||
void AP_AHRS_NavEKF::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||
{
|
||||
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
||||
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
|
||||
|
|
|
@ -157,7 +157,7 @@ public:
|
|||
bool get_vert_pos_rate(float &velocity) const;
|
||||
|
||||
// write optical flow measurements to EKF
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset);
|
||||
void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset);
|
||||
|
||||
// write body odometry measurements to the EKF
|
||||
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset);
|
||||
|
|
Loading…
Reference in New Issue