mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_AHRS: fix get_relative_position_NE_home calcalation
This commit is contained in:
parent
1875f0218f
commit
d6845a911a
@ -799,8 +799,8 @@ bool AP_AHRS_NavEKF::get_relative_position_NED_home(Vector3f &vec) const
|
|||||||
|
|
||||||
Vector3f offset = location_3d_diff_NED(originLLH, _home);
|
Vector3f offset = location_3d_diff_NED(originLLH, _home);
|
||||||
|
|
||||||
vec.x = originNED.x + offset.x;
|
vec.x = originNED.x - offset.x;
|
||||||
vec.y = originNED.y + offset.y;
|
vec.y = originNED.y - offset.y;
|
||||||
vec.z = originNED.z - offset.z;
|
vec.z = originNED.z - offset.z;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -848,8 +848,8 @@ bool AP_AHRS_NavEKF::get_relative_position_NE_home(Vector2f &posNE) const
|
|||||||
|
|
||||||
Vector2f offset = location_diff(originLLH, _home);
|
Vector2f offset = location_diff(originLLH, _home);
|
||||||
|
|
||||||
posNE.x = originNE.x + offset.x;
|
posNE.x = originNE.x - offset.x;
|
||||||
posNE.y = originNE.y + offset.y;
|
posNE.y = originNE.y - offset.y;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user