mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF3: fix writeOptFlowMeas signature
const some of the vectors, stop taking references to scalars that aren't being changed
This commit is contained in:
parent
d8aa8d2b71
commit
be9235a581
@ -1126,7 +1126,7 @@ bool NavEKF3::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
|
// 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.
|
// 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
|
// posOffset is the XYZ flow sensor position in the body frame in m
|
||||||
void NavEKF3::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
|
void NavEKF3::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||||
{
|
{
|
||||||
if (core) {
|
if (core) {
|
||||||
for (uint8_t i=0; i<num_cores; i++) {
|
for (uint8_t i=0; i<num_cores; i++) {
|
||||||
|
@ -206,7 +206,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
|
// 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.
|
// 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
|
// 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);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Write body frame linear and angular displacement measurements from a visual odometry sensor
|
* Write body frame linear and angular displacement measurements from a visual odometry sensor
|
||||||
|
@ -161,7 +161,7 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam
|
|||||||
|
|
||||||
// write the raw optical flow measurements
|
// write the raw optical flow measurements
|
||||||
// this needs to be called externally.
|
// this needs to be called externally.
|
||||||
void NavEKF3_core::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
|
void NavEKF3_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
|
||||||
{
|
{
|
||||||
// limit update rate to maximum allowed by sensor buffers
|
// limit update rate to maximum allowed by sensor buffers
|
||||||
if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) {
|
if ((imuSampleTime_ms - flowMeaTime_ms) < frontend->sensorIntervalMin_ms) {
|
||||||
|
@ -202,7 +202,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
|
// 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.
|
// 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
|
// 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
|
// 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;
|
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