diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 72bea649de34728eab1a150907ccc195f83cd00a..2703dbf160ccc2f9ba67b9a5bd18d00e68619492 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -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