Plane: Only allow speed changes in GUIDED and AUTO modes.

This commit is contained in:
Michael Day 2016-06-07 08:22:44 -04:00
parent 6284d513f5
commit 2c0f0a04d8

View File

@ -1226,6 +1226,15 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
switch(packet.command) {
case MAV_CMD_DO_CHANGE_SPEED:
//if we're in failsafe modes (e.g., RTL, LOITER) or in pilot
//controlled modes (e.g., MANUAL, TRAINING)
//this comand should be ignored since it comes in from GCS
//or a companion computer:
if (plane.control_mode != GUIDED && plane.control_mode != AUTO) {
result = MAV_RESULT_FAILED;
break;
}
result = MAV_RESULT_FAILED;
AP_Mission::Mission_Command cmd;
if (AP_Mission::mavlink_cmd_long_to_mission_cmd(packet, cmd)