mirror of https://github.com/ArduPilot/ardupilot
Copter: 32 servo conversion
This commit is contained in:
parent
32f8062b3e
commit
424c3b953a
|
@ -318,8 +318,8 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
|
|||
// check we have an ESC present for every SERVOx_FUNCTION = motorx
|
||||
// find and report first missing ESC, extra ESCs are OK
|
||||
AP_ToshibaCAN *tcan = AP_ToshibaCAN::get_tcan(tcan_index);
|
||||
const uint16_t motors_mask = copter.motors->get_motor_mask();
|
||||
const uint16_t esc_mask = tcan->get_present_mask();
|
||||
const uint32_t motors_mask = copter.motors->get_motor_mask();
|
||||
const uint32_t esc_mask = tcan->get_present_mask();
|
||||
uint8_t escs_missing = 0;
|
||||
uint8_t first_missing = 0;
|
||||
for (uint8_t i = 0; i < 16; i++) {
|
||||
|
|
|
@ -45,7 +45,7 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void)
|
|||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// setup AP_Motors outputs for failsafe
|
||||
uint16_t mask = copter.motors->get_motor_mask();
|
||||
uint32_t mask = copter.motors->get_motor_mask();
|
||||
hal.rcout->set_failsafe_pwm(mask, copter.motors->get_pwm_output_min());
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue