From 56db91d0c3063ec01b24283615fdda387a8eb620 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 16 May 2022 07:29:35 +1000 Subject: [PATCH] Plane: 32 servo conversion --- ArduPlane/afs_plane.cpp | 2 +- ArduPlane/quadplane.cpp | 2 +- ArduPlane/servos.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/afs_plane.cpp b/ArduPlane/afs_plane.cpp index 893d1208b3..f01297470b 100644 --- a/ArduPlane/afs_plane.cpp +++ b/ArduPlane/afs_plane.cpp @@ -84,7 +84,7 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void) #if HAL_QUADPLANE_ENABLED if (plane.quadplane.available()) { // setup AP_Motors outputs for failsafe - uint16_t mask = plane.quadplane.motors->get_motor_mask(); + uint32_t mask = plane.quadplane.motors->get_motor_mask(); hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); } #endif diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8288469939..ff3b118dc6 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -711,7 +711,7 @@ bool QuadPlane::setup(void) // setup the trim of any motors used by AP_Motors so I/O board // failsafe will disable motors - uint16_t mask = plane.quadplane.motors->get_motor_mask(); + uint32_t mask = plane.quadplane.motors->get_motor_mask(); hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); // default QAssist state as set with Q_OPTIONS diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 7381b98083..b51ebd020d 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -985,7 +985,7 @@ void Plane::servos_output(void) // support MANUAL_RCMASK if (g2.manual_rc_mask.get() != 0 && control_mode == &mode_manual) { - SRV_Channels::copy_radio_in_out_mask(uint16_t(g2.manual_rc_mask.get())); + SRV_Channels::copy_radio_in_out_mask(uint32_t(g2.manual_rc_mask.get())); } SRV_Channels::calc_pwm();