mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2 : correct variable typo
receverPosDownMax -> receiverPosDownMax receverPosDownMin -> receiverPosDownMin
This commit is contained in:
parent
721ede206d
commit
bd76c30768
@ -323,18 +323,18 @@ void NavEKF2_core::FuseRngBcnStatic()
|
|||||||
ftype delta = receiverPos.z - bcnMidPosD;
|
ftype delta = receiverPos.z - bcnMidPosD;
|
||||||
|
|
||||||
// calcuate the two hypothesis for our vertical position
|
// calcuate the two hypothesis for our vertical position
|
||||||
ftype receverPosDownMax;
|
ftype receiverPosDownMax;
|
||||||
ftype receverPosDownMin;
|
ftype receiverPosDownMin;
|
||||||
if (delta >= 0.0f) {
|
if (delta >= 0.0f) {
|
||||||
receverPosDownMax = receiverPos.z;
|
receiverPosDownMax = receiverPos.z;
|
||||||
receverPosDownMin = receiverPos.z - 2.0f * delta;
|
receiverPosDownMin = receiverPos.z - 2.0f * delta;
|
||||||
} else {
|
} else {
|
||||||
receverPosDownMax = receiverPos.z - 2.0f * delta;
|
receiverPosDownMax = receiverPos.z - 2.0f * delta;
|
||||||
receverPosDownMin = receiverPos.z;
|
receiverPosDownMin = receiverPos.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
bcnPosOffsetMax = stateStruct.position.z - receverPosDownMin;
|
bcnPosOffsetMax = stateStruct.position.z - receiverPosDownMin;
|
||||||
bcnPosOffsetMin = stateStruct.position.z - receverPosDownMax;
|
bcnPosOffsetMin = stateStruct.position.z - receiverPosDownMax;
|
||||||
} else {
|
} else {
|
||||||
// We are using the beacons as the primary height reference, so don't modify their vertical position
|
// We are using the beacons as the primary height reference, so don't modify their vertical position
|
||||||
bcnPosOffset = 0.0f;
|
bcnPosOffset = 0.0f;
|
||||||
|
Loading…
Reference in New Issue
Block a user