Plane: added ONESHOT_MASK parameter

after discussion with Paul on servo latency
This commit is contained in:
Andrew Tridgell 2021-07-17 18:11:28 +10:00 committed by Randy Mackay
parent d67f82e02d
commit 401534ac89
3 changed files with 14 additions and 1 deletions

View File

@ -1249,6 +1249,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @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
};

View File

@ -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[];

View File

@ -121,6 +121,10 @@ void Plane::init_ardupilot()
// 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();