mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
SRV_Channel: added get_motor_function()
for correct handling of motors 8 and above
This commit is contained in:
parent
45d6f3bf75
commit
381e2fd69a
@ -405,6 +405,14 @@ public:
|
|||||||
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap);
|
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap);
|
||||||
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
|
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
|
||||||
|
|
||||||
|
// given a zero-based motor channel, return the k_motor function for that channel
|
||||||
|
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel) {
|
||||||
|
if (channel < 8) {
|
||||||
|
return SRV_Channel::Aux_servo_function_t(SRV_Channel::k_motor1+channel);
|
||||||
|
}
|
||||||
|
return SRV_Channel::Aux_servo_function_t((SRV_Channel::k_motor9+(channel-8)));
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
struct {
|
struct {
|
||||||
bool k_throttle_reversible:1;
|
bool k_throttle_reversible:1;
|
||||||
|
Loading…
Reference in New Issue
Block a user