Copter: integrate variable max num commands

This commit is contained in:
Randy Mackay 2014-03-12 15:24:30 +09:00
parent fcea127537
commit 7b6906ae3f
1 changed files with 1 additions and 1 deletions

View File

@ -1534,7 +1534,7 @@ mission_item_send_failed:
}
// 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;