mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
GCS_MAVLink: return MAV_RESULT_FAILED from do_aux_function if invalid function
This commit is contained in:
parent
30539ac8ac
commit
115e895c82
@ -2473,7 +2473,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_lon
|
||||
}
|
||||
const RC_Channel::AUX_FUNC aux_func = (RC_Channel::AUX_FUNC)packet.param1;
|
||||
const RC_Channel::AuxSwitchPos position = (RC_Channel::AuxSwitchPos)packet.param2;
|
||||
rc().do_aux_function(aux_func, position);
|
||||
if (!rc().do_aux_function(aux_func, position)) {
|
||||
// note that this is not quite right; we could be more nuanced
|
||||
// about our return code here.
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user