Copter: Add a switch option to enable/disable RC_Override
This commit is contained in:
parent
d579e086cf
commit
10e6fe43dd
@ -288,6 +288,7 @@ private:
|
||||
uint8_t in_arming_delay : 1; // 24 // true while we are armed but waiting to spin motors
|
||||
uint8_t initialised_params : 1; // 25 // true when the all parameters have been initialised. we cannot send parameters to the GCS until this is done
|
||||
uint8_t compass_init_location : 1; // 26 // true when the compass's initial location has been set
|
||||
uint8_t rc_override_enable : 1; // 27 // aux switch rc_override is allowed
|
||||
};
|
||||
uint32_t value;
|
||||
} ap_t;
|
||||
|
@ -761,6 +761,13 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
// or for complete GCS control of switch position
|
||||
// and RC PWM values.
|
||||
if(msg->sysid != copter.g.sysid_my_gcs) break; // Only accept control from our gcs
|
||||
if (!copter.ap.rc_override_enable) {
|
||||
if (copter.failsafe.rc_override_active) { // if overrides were active previously, disable them
|
||||
copter.failsafe.rc_override_active = false;
|
||||
hal.rcin->clear_overrides();
|
||||
}
|
||||
break;
|
||||
}
|
||||
mavlink_rc_channels_override_t packet;
|
||||
int16_t v[8];
|
||||
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
||||
|
@ -74,6 +74,7 @@ enum aux_sw_func {
|
||||
AUXSW_INVERTED = 43, // enable inverted flight
|
||||
AUXSW_WINCH_ENABLE = 44, // winch enable/disable
|
||||
AUXSW_WINCH_CONTROL = 45, // winch control
|
||||
AUXSW_RC_OVERRIDE_ENABLE = 46, // enable RC Override
|
||||
AUXSW_SWITCH_MAX,
|
||||
};
|
||||
|
||||
|
@ -198,6 +198,7 @@ void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
|
||||
case AUXSW_AVOID_PROXIMITY:
|
||||
case AUXSW_INVERTED:
|
||||
case AUXSW_WINCH_ENABLE:
|
||||
case AUXSW_RC_OVERRIDE_ENABLE:
|
||||
do_aux_switch_function(ch_option, ch_flag);
|
||||
break;
|
||||
}
|
||||
@ -657,6 +658,20 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case AUXSW_RC_OVERRIDE_ENABLE:
|
||||
// Allow or disallow RC_Override
|
||||
switch (ch_flag) {
|
||||
case AUX_SWITCH_HIGH: {
|
||||
ap.rc_override_enable = true;
|
||||
break;
|
||||
}
|
||||
case AUX_SWITCH_LOW: {
|
||||
ap.rc_override_enable = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user