mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mission: support for MAV_CMD_CONTINUE_AND_CHANGE_ALT
This commit is contained in:
parent
dca99a9643
commit
b36c1b2c3d
@ -512,6 +512,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
||||
cmd.p1 = packet.param1; // minimum pitch (plane only)
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
|
||||
copy_location = true; // only using alt
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
|
||||
copy_location = true;
|
||||
cmd.p1 = packet.param1; // delay at waypoint in seconds
|
||||
@ -777,6 +781,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
||||
packet.param1 = cmd.p1; // minimum pitch (plane only)
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
|
||||
copy_location = true; //only using alt.
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
|
||||
copy_location = true;
|
||||
packet.param1 = cmd.p1; // delay at waypoint in seconds
|
||||
|
Loading…
Reference in New Issue
Block a user