mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Motors: rc_write handles motors 9 to 12
This commit is contained in:
parent
544d6aa8a0
commit
d00725b2ed
@ -198,10 +198,14 @@ void AP_Motors::add_motor_num(int8_t motor_num)
|
||||
// ensure valid motor number is provided
|
||||
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
||||
uint8_t chan;
|
||||
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+motor_num);
|
||||
SRV_Channel::Aux_servo_function_t function;
|
||||
if (motor_num < 8) {
|
||||
function = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+motor_num);
|
||||
} else {
|
||||
function = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor9+(motor_num-8));
|
||||
}
|
||||
SRV_Channels::set_aux_channel_default(function, motor_num);
|
||||
if (SRV_Channels::find_channel((SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+motor_num),
|
||||
chan) && chan != motor_num) {
|
||||
if (SRV_Channels::find_channel(function, chan) && chan != motor_num) {
|
||||
_motor_map[motor_num] = chan;
|
||||
_motor_map_mask |= 1U<<motor_num;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user