mavlink: support MAV_FRAME_GLOBAL_RELATIVE_ALT

this allows for relative altitude, but global lat/lon

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1791 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-03-19 10:23:08 +00:00
parent d70703aa62
commit 2850ac6c74

View File

@ -535,6 +535,18 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
tell_command.alt = -packet.z*1.0e2 + home.alt;
break;
}
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
{
if (!home_is_set) {
send_text_P(SEVERITY_MEDIUM, PSTR("Refusing relative alt wp: home not set"));
return;
}
tell_command.lat = 1.0e7*packet.x; // in as DD converted to * t7
tell_command.lng = 1.0e7*packet.y; // in as DD converted to * t7
tell_command.alt = packet.z*1.0e2 + home.alt;
break;
}
}
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields