Plane: 32 servo conversion

This commit is contained in:
Andrew Tridgell 2022-05-16 07:29:35 +10:00
parent 424c3b953a
commit 56db91d0c3
3 changed files with 3 additions and 3 deletions

View File

@ -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

View File

@ -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

View File

@ -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();