mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: fix writeOptFlowMeas signature
const some of the vectors, stop taking references to scalars that aren't being changed
This commit is contained in:
parent
306a40bb77
commit
d8aa8d2b71
@ -1082,7 +1082,7 @@ bool NavEKF2::use_compass(void) const
|
||||
// The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
|
||||
// msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
|
||||
// posOffset is the XYZ flow sensor position in the body frame in m
|
||||
void NavEKF2::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
|
||||
void NavEKF2::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||
{
|
||||
if (core) {
|
||||
for (uint8_t i=0; i<num_cores; i++) {
|
||||
|
@ -212,7 +212,7 @@ public:
|
||||
// The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
|
||||
// msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
|
||||
// posOffset is the XYZ flow sensor position in the body frame in m
|
||||
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);
|
||||
|
||||
// return data for debugging optical flow fusion for the specified instance
|
||||
// An out of range instance (eg -1) returns data for the the primary instance
|
||||
|
@ -117,7 +117,7 @@ void NavEKF2_core::readRangeFinder(void)
|
||||
|
||||
// write the raw optical flow measurements
|
||||
// this needs to be called externally.
|
||||
void NavEKF2_core::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
|
||||
void NavEKF2_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||
{
|
||||
// The raw measurements need to be optical flow rates in radians/second averaged across the time since the last update
|
||||
// The PX4Flow sensor outputs flow rates with the following axis and sign conventions:
|
||||
|
@ -198,7 +198,7 @@ public:
|
||||
// The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
|
||||
// msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
|
||||
// posOffset is the XYZ flow sensor position in the body frame in m
|
||||
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);
|
||||
|
||||
// return data for debugging optical flow fusion
|
||||
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const;
|
||||
|
Loading…
Reference in New Issue
Block a user