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;
|
||||
|
||||
// calcuate the two hypothesis for our vertical position
|
||||
ftype receverPosDownMax;
|
||||
ftype receverPosDownMin;
|
||||
ftype receiverPosDownMax;
|
||||
ftype receiverPosDownMin;
|
||||
if (delta >= 0.0f) {
|
||||
receverPosDownMax = receiverPos.z;
|
||||
receverPosDownMin = receiverPos.z - 2.0f * delta;
|
||||
receiverPosDownMax = receiverPos.z;
|
||||
receiverPosDownMin = receiverPos.z - 2.0f * delta;
|
||||
} else {
|
||||
receverPosDownMax = receiverPos.z - 2.0f * delta;
|
||||
receverPosDownMin = receiverPos.z;
|
||||
receiverPosDownMax = receiverPos.z - 2.0f * delta;
|
||||
receiverPosDownMin = receiverPos.z;
|
||||
}
|
||||
|
||||
bcnPosOffsetMax = stateStruct.position.z - receverPosDownMin;
|
||||
bcnPosOffsetMin = stateStruct.position.z - receverPosDownMax;
|
||||
bcnPosOffsetMax = stateStruct.position.z - receiverPosDownMin;
|
||||
bcnPosOffsetMin = stateStruct.position.z - receiverPosDownMax;
|
||||
} else {
|
||||
// We are using the beacons as the primary height reference, so don't modify their vertical position
|
||||
bcnPosOffset = 0.0f;
|
||||
|
Loading…
Reference in New Issue
Block a user