GCS_Common: send_local_position uses offset from origin

This commit is contained in:
Sharvashish Das 2020-08-27 09:51:33 +09:00 committed by Andrew Tridgell
parent 56e44c46ca
commit 80e2dbc9f2

View File

@ -2271,7 +2271,7 @@ void GCS_MAVLINK::send_local_position() const
const AP_AHRS &ahrs = AP::ahrs();
Vector3f local_position, velocity;
if (!ahrs.get_relative_position_NED_home(local_position) ||
if (!ahrs.get_relative_position_NED_origin(local_position) ||
!ahrs.get_velocity_NED(velocity)) {
// we don't know the position and velocity
return;