From cff692ca4881eb00753247b0e9f5932ce021dbbc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Jul 2017 17:01:33 +1000 Subject: [PATCH] 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 --- ArduPlane/Parameters.cpp | 7 +++++++ ArduPlane/Parameters.h | 3 +++ ArduPlane/px4_mixer.cpp | 6 ++++++ ArduPlane/servos.cpp | 7 ++++++- 4 files changed, 22 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 95ccb06386..9a0c61bfe9 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1184,6 +1184,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard 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 }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 072cddd2bb..d4da95fe9c 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -542,6 +542,9 @@ public: // dual motor tailsitter rudder to differential thrust scaling: 0-100% 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[]; diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index 5683073416..65e2f8f9a3 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -209,8 +209,14 @@ uint16_t Plane::create_mixer(char *buf, uint16_t buf_size, const char *filename) { char *buf0 = buf; 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++) { + if ((1U<push();