mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_AHRS: fix get_relative_position_NE_home calcalation
This commit is contained in:
parent
7fee271e73
commit
c1e9a30c1d
@ -790,8 +790,8 @@ bool AP_AHRS_NavEKF::get_relative_position_NED_home(Vector3f &vec) const
|
||||
|
||||
Vector3f offset = location_3d_diff_NED(originLLH, _home);
|
||||
|
||||
vec.x = originNED.x + offset.x;
|
||||
vec.y = originNED.y + offset.y;
|
||||
vec.x = originNED.x - offset.x;
|
||||
vec.y = originNED.y - offset.y;
|
||||
vec.z = originNED.z - offset.z;
|
||||
return true;
|
||||
}
|
||||
@ -839,8 +839,8 @@ bool AP_AHRS_NavEKF::get_relative_position_NE_home(Vector2f &posNE) const
|
||||
|
||||
Vector2f offset = location_diff(originLLH, _home);
|
||||
|
||||
posNE.x = originNE.x + offset.x;
|
||||
posNE.y = originNE.y + offset.y;
|
||||
posNE.x = originNE.x - offset.x;
|
||||
posNE.y = originNE.y - offset.y;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user