From 7ff379850c29cc946d4745977f1629bfffcb2aed Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 12 Mar 2014 15:25:51 +0900 Subject: [PATCH] Rover: integrate variable max num commands --- APMrover2/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index b09bc393bd..99723de339 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -1438,7 +1438,7 @@ mission_item_send_failed: if (mavlink_check_target(packet.target_system,packet.target_component)) break; // start waypoint receiving - if (packet.count > AP_MISSION_MAX_COMMANDS) { + if (packet.count > mission.num_commands_max()) { // send NAK mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_NO_SPACE); break;