mavlink: paranoia setting of failsafe when forcing AUTO mode

this shouldn't be needed, but will do no harm, and I thought I saw
this fail in a test
This commit is contained in:
Andrew Tridgell 2011-11-28 15:58:57 +11:00
parent 7214e2ec06
commit e61d945874

View File

@ -1071,6 +1071,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_ACTION_SET_AUTO:
set_mode(AUTO);
result=1;
// clearing failsafe should not be needed
// here. Added based on some puzzling results in
// the simulator (tridge)
failsafe = FAILSAFE_NONE;
break;
case MAV_ACTION_STORAGE_READ: