AP_Motors: allow arbitrary mapping of channels on multirotors
using RCn_FUNCTION with motor1, motor2 etc
This commit is contained in:
parent
2777ff63ba
commit
77af00c5e1
@ -415,8 +415,15 @@ void AP_MotorsMatrix::add_motor_raw(int8_t motor_num, float roll_fac, float pitc
|
|||||||
// set order that motor appears in test
|
// set order that motor appears in test
|
||||||
_test_order[motor_num] = testing_order;
|
_test_order[motor_num] = testing_order;
|
||||||
|
|
||||||
// disable this channel from being used by RC_Channel_aux
|
uint8_t chan;
|
||||||
RC_Channel_aux::disable_aux_channel(motor_num);
|
if (RC_Channel_aux::find_channel((RC_Channel_aux::Aux_servo_function_t)(RC_Channel_aux::k_motor1+motor_num),
|
||||||
|
chan)) {
|
||||||
|
_motor_map[motor_num] = chan;
|
||||||
|
_motor_map_mask |= 1U<<motor_num;
|
||||||
|
} else {
|
||||||
|
// disable this channel from being used by RC_Channel_aux
|
||||||
|
RC_Channel_aux::disable_aux_channel(motor_num);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -70,5 +70,9 @@ void AP_Motors::armed(bool arm)
|
|||||||
*/
|
*/
|
||||||
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
||||||
{
|
{
|
||||||
|
if (_motor_map_mask & (1U<<chan)) {
|
||||||
|
// we have a mapped motor number for this channel
|
||||||
|
chan = _motor_map[chan];
|
||||||
|
}
|
||||||
hal.rcout->write(chan, pwm);
|
hal.rcout->write(chan, pwm);
|
||||||
}
|
}
|
||||||
|
@ -160,5 +160,9 @@ protected:
|
|||||||
float _batt_voltage; // latest battery voltage reading
|
float _batt_voltage; // latest battery voltage reading
|
||||||
float _batt_current; // latest battery current reading
|
float _batt_current; // latest battery current reading
|
||||||
float _air_density_ratio; // air density / sea level density - decreases in altitude
|
float _air_density_ratio; // air density / sea level density - decreases in altitude
|
||||||
|
|
||||||
|
// mapping to output channels
|
||||||
|
uint8_t _motor_map[AP_MOTORS_MAX_NUM_MOTORS];
|
||||||
|
uint16_t _motor_map_mask;
|
||||||
};
|
};
|
||||||
#endif // __AP_MOTORS_CLASS_H__
|
#endif // __AP_MOTORS_CLASS_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user