mirror of https://github.com/ArduPilot/ardupilot
Plane: implement MANUAL_RCMASK
this replaces the functionality of the old "with input" aileron/elevator functions, but in a much more flexible way. It means that people who want to fly in MANAUL mode will have the ability to have full control of trims and mixing using transmitter mixers if they need that functionality
This commit is contained in:
parent
20bddf4d5a
commit
bf6853d3fe
|
@ -1184,6 +1184,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),
|
AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),
|
||||||
|
|
||||||
|
// @Param: MANUAL_RCMASK
|
||||||
|
// @DisplayName: Manual R/C pass-through mask
|
||||||
|
// @Description: Mask of R/C channels to pass directly to corresponding output channel when in MANUAL mode. When in any more except MANUAL the channels selected with this option behave normally. This parameter is designed to allow for complex mixing strategies to be used for MANUAL flight using transmitter based mixing. Note that when this option is used you need to be very careful with pre-flight checks to ensure that the output is correct both in MANUAL and non-MANUAL modes.
|
||||||
|
// @Bitmask: 0:Chan1,1:Chan2,2:Chan3,3:Chan4,4:Chan5,5:Chan6,6:Chan7,7:Chan8,8:Chan9,9:Chan10,10:Chan11,11:Chan12,12:Chan13,13:Chan14,14:Chan15,15:Chan16
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("MANUAL_RCMASK", 10, ParametersG2, manual_rc_mask, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -542,6 +542,9 @@ public:
|
||||||
|
|
||||||
// dual motor tailsitter rudder to differential thrust scaling: 0-100%
|
// dual motor tailsitter rudder to differential thrust scaling: 0-100%
|
||||||
AP_Int8 rudd_dt_gain;
|
AP_Int8 rudd_dt_gain;
|
||||||
|
|
||||||
|
// mask of channels to do manual pass-thru for
|
||||||
|
AP_Int32 manual_rc_mask;
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const AP_Param::Info var_info[];
|
extern const AP_Param::Info var_info[];
|
||||||
|
|
|
@ -209,8 +209,14 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename)
|
||||||
{
|
{
|
||||||
char *buf0 = buf;
|
char *buf0 = buf;
|
||||||
uint16_t buf_size0 = buf_size;
|
uint16_t buf_size0 = buf_size;
|
||||||
|
uint16_t manual_mask = uint16_t(g2.manual_rc_mask.get());
|
||||||
|
|
||||||
for (uint8_t i=0; i<8; i++) {
|
for (uint8_t i=0; i<8; i++) {
|
||||||
|
if ((1U<<i) & manual_mask) {
|
||||||
|
// handle MANUAL_RCMASK channels
|
||||||
|
mix_passthrough(buf, buf_size, i, i);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
SRV_Channel::Aux_servo_function_t function = SRV_Channels::channel_function(i);
|
SRV_Channel::Aux_servo_function_t function = SRV_Channels::channel_function(i);
|
||||||
switch (function) {
|
switch (function) {
|
||||||
case SRV_Channel::k_aileron:
|
case SRV_Channel::k_aileron:
|
||||||
|
|
|
@ -757,8 +757,13 @@ void Plane::servos_output(void)
|
||||||
// run vtail and elevon mixers
|
// run vtail and elevon mixers
|
||||||
servo_output_mixers();
|
servo_output_mixers();
|
||||||
|
|
||||||
SRV_Channels::calc_pwm();
|
// support MANUAL_RCMASK
|
||||||
|
if (g2.manual_rc_mask.get() != 0) {
|
||||||
|
SRV_Channels::copy_radio_in_out_mask(uint16_t(g2.manual_rc_mask.get()));
|
||||||
|
}
|
||||||
|
|
||||||
|
SRV_Channels::calc_pwm();
|
||||||
|
|
||||||
SRV_Channels::output_ch_all();
|
SRV_Channels::output_ch_all();
|
||||||
|
|
||||||
hal.rcout->push();
|
hal.rcout->push();
|
||||||
|
|
Loading…
Reference in New Issue