AP_Mission: add missing breaks to case statement

This commit is contained in:
Randy Mackay 2015-07-17 11:25:42 +09:00
parent 0acfcbfa81
commit 429346f4bc
1 changed files with 2 additions and 0 deletions

View File

@ -676,6 +676,7 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
cmd.content.guided_limits.alt_min = packet.param2; // min alt below which the command will be aborted. 0 for no lower alt limit
cmd.content.guided_limits.alt_max = packet.param3; // max alt above which the command will be aborted. 0 for no upper alt limit
cmd.content.guided_limits.horiz_max = packet.param4;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
break;
case MAV_CMD_DO_AUTOTUNE_ENABLE: // MAV ID: 211
cmd.p1 = packet.param1; // disable=0 enable=1
@ -988,6 +989,7 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
packet.param2 = cmd.content.guided_limits.alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
packet.param3 = cmd.content.guided_limits.alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
packet.param4 = cmd.content.guided_limits.horiz_max;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
break;
case MAV_CMD_DO_AUTOTUNE_ENABLE:
packet.param1 = cmd.p1; // disable=0 enable=1