mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Sub: Remove DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
This commit is contained in:
parent
1bd6480a41
commit
6a80fe3c22
@ -19,7 +19,6 @@
|
||||
//#define AC_RALLY ENABLED // enable rally points library
|
||||
//#define AC_TERRAIN ENABLED // enable terrain library (Must also enable Rally)
|
||||
//#define OPTFLOW ENABLED // enable optical flow sensor support
|
||||
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
|
||||
|
||||
// User Hooks : For User Developed code that you wish to run
|
||||
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
|
||||
|
@ -923,16 +923,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
|
||||
case MAVLINK_MSG_ID_SET_MODE: { // MAV ID: 11
|
||||
#ifdef DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
|
||||
if (!sub.failsafe.manual_control) {
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&sub, &Sub::gcs_set_mode, bool, uint8_t));
|
||||
} else {
|
||||
// don't allow mode changes while in radio failsafe
|
||||
mavlink_msg_command_ack_send_buf(msg, chan, MAVLINK_MSG_ID_SET_MODE, MAV_RESULT_FAILED);
|
||||
}
|
||||
#else
|
||||
handle_set_mode(msg, FUNCTOR_BIND(&sub, &Sub::gcs_set_mode, bool, uint8_t));
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user