Rover: integrate variable max num commands

This commit is contained in:
Randy Mackay 2014-03-12 15:25:51 +09:00
parent fdec917607
commit 7ff379850c
1 changed files with 1 additions and 1 deletions

View File

@ -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;