From 401534ac89744b7554b4e2b988370cd8b0224e47 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 17 Jul 2021 18:11:28 +1000 Subject: [PATCH] Plane: added ONESHOT_MASK parameter after discussion with Paul on servo latency --- ArduPlane/Parameters.cpp | 7 +++++++ ArduPlane/Parameters.h | 2 ++ ArduPlane/system.cpp | 6 +++++- 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index c2a8aa6260..4ea7d7efea 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1248,6 +1248,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Increment: 1 // @User: Standard AP_GROUPINFO("MAN_EXPO_RUDDER", 31, ParametersG2, man_expo_rudder, 0), + + // @Param: ONESHOT_MASK + // @DisplayName: Oneshot output mask + // @Description: Mask of output channels to use oneshot on + // @User: Advanced + // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0), AP_GROUPEND }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 8b7fa63cf3..2220b664d4 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -573,6 +573,8 @@ public: AP_Int8 man_expo_roll; AP_Int8 man_expo_pitch; AP_Int8 man_expo_rudder; + + AP_Int32 oneshot_mask; }; extern const AP_Param::Info var_info[]; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 1585004193..6fd7404522 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -120,7 +120,11 @@ void Plane::init_ardupilot() // don't initialise aux rc output until after quadplane is setup as // that can change initial values of channels init_rc_out_aux(); - + + if (g2.oneshot_mask != 0) { + hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); + } + // choose the nav controller set_nav_controller();