mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed motor channel handling
This commit is contained in:
parent
381e2fd69a
commit
92ee05b925
|
@ -446,7 +446,7 @@ QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) :
|
|||
void QuadPlane::setup_default_channels(uint8_t num_motors)
|
||||
{
|
||||
for (uint8_t i=0; i<num_motors; i++) {
|
||||
SRV_Channels::set_aux_channel_default((SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+i), CH_5+i);
|
||||
SRV_Channels::set_aux_channel_default(SRV_Channels::get_motor_function(i), CH_5+i);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -595,7 +595,7 @@ bool QuadPlane::setup(void)
|
|||
// setup the trim of any motors used by AP_Motors so px4io
|
||||
// failsafe will disable motors
|
||||
for (uint8_t i=0; i<8; i++) {
|
||||
SRV_Channel::Aux_servo_function_t func = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+i);
|
||||
SRV_Channel::Aux_servo_function_t func = SRV_Channels::get_motor_function(i);
|
||||
SRV_Channels::set_failsafe_pwm(func, thr_min_pwm);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue