Copter: support SET_POSITION_TARGET with WGS84 altitudes

This commit is contained in:
Jonathan Challinger 2016-01-11 13:29:06 -08:00 committed by Randy Mackay
parent 081beacb8d
commit 5f610fdcba

View File

@ -1717,7 +1717,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_FRAME_GLOBAL_INT:
default:
loc.flags.relative_alt = false;
// Copter does not support navigation to absolute altitudes. This convert the WGS84 altitude
// to a home-relative altitude before passing it to the navigation controller
loc.alt -= copter.ahrs.get_home().alt;
loc.flags.relative_alt = true;
loc.flags.terrain_alt = false;
break;
}