mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP,AC Add ability to override an altitude in any auto mode, on the current active target
This commit is contained in:
parent
fc4f4d76c9
commit
939ee1f4a9
@ -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;
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user