AP_Periph: 32 servo conversion

This commit is contained in:
Andrew Tridgell 2022-05-16 07:29:45 +10:00
parent 56db91d0c3
commit 10d7a559d2
1 changed files with 1 additions and 1 deletions

View File

@ -49,7 +49,7 @@ void AP_Periph_FW::rcout_init()
SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000);
}
uint16_t esc_mask = 0;
uint32_t esc_mask = 0;
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
uint8_t chan;