AP,AC Add ability to override an altitude in any auto mode, on the current active target

This commit is contained in:
Michael Oborne 2012-09-30 07:29:33 +08:00
parent 95763e610b
commit a38fef65c7
2 changed files with 32 additions and 0 deletions

View File

@ -1542,6 +1542,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
msg->compid,
0);
} else if(packet.current == 3) { //current = 3 is a flag to tell us this is a alt change only
// add home alt if needed
if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) {
tell_command.alt += home.alt;
}
set_new_altitude(tell_command.alt);
// verify we recevied the command
mavlink_msg_mission_ack_send(
chan,
msg->sysid,
msg->compid,
0);
} else {
// Check if receiving waypoints (mission upload expected)
if (!waypoint_receiving) break;

View File

@ -1541,6 +1541,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
msg->compid,
0);
} else if(packet.current == 3) { //current = 3 is a flag to tell us this is a alt change only
// add home alt if needed
if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) {
tell_command.alt += home.alt;
}
next_WP.alt = tell_command.alt;
// verify we recevied the command
mavlink_msg_mission_ack_send(
chan,
msg->sysid,
msg->compid,
0);
} else {
// Check if receiving waypoints (mission upload expected)
if (!waypoint_receiving) {