diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index 92dd9c1638..1909d02486 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -26,6 +26,20 @@ #define CH_16 15 #define CH_17 16 #define CH_18 17 +#define CH_19 18 +#define CH_20 19 +#define CH_21 20 +#define CH_22 21 +#define CH_23 22 +#define CH_24 23 +#define CH_25 24 +#define CH_26 25 +#define CH_27 26 +#define CH_28 27 +#define CH_29 28 +#define CH_30 29 +#define CH_31 30 +#define CH_32 31 #define CH_NONE 255 #endif @@ -57,15 +71,15 @@ public: * so that output scaling can be performed correctly. The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - virtual void set_reversible_mask(uint16_t chanmask) {} + virtual void set_reversible_mask(uint32_t chanmask) {} /* * mark the channels in chanmask as reversed. * The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - virtual void set_reversed_mask(uint16_t chanmask) {} - virtual uint16_t get_reversed_mask() { return 0; } + virtual void set_reversed_mask(uint32_t chanmask) {} + virtual uint32_t get_reversed_mask() { return 0; } /* * Update channel masks at 1Hz allowing for actions such as dshot commands to be sent @@ -165,7 +179,7 @@ public: as those in the same channel timer groups) may also be stopped, depending on the implementation */ - virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t chanmask) { return false; } + virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask) { return false; } /* write a set of bytes to an ESC, using settings from @@ -242,7 +256,7 @@ public: DSHOT_ESC_BLHELI = 1 }; - virtual void set_output_mode(uint16_t mask, enum output_mode mode) {} + virtual void set_output_mode(uint32_t mask, enum output_mode mode) {} /* * get output mode banner to inform user of how outputs are configured @@ -263,18 +277,18 @@ public: enable telemetry request for a mask of channels. This is used with DShot to get telemetry feedback */ - virtual void set_telem_request_mask(uint16_t mask) {} + virtual void set_telem_request_mask(uint32_t mask) {} /* enable bi-directional telemetry request for a mask of channels. This is used with DShot to get telemetry feedback */ - virtual void set_bidir_dshot_mask(uint16_t mask) {} + virtual void set_bidir_dshot_mask(uint32_t mask) {} /* mark escs as active for the purpose of sending dshot commands */ - virtual void set_active_escs_mask(uint16_t mask) {} + virtual void set_active_escs_mask(uint32_t mask) {} /* Set the dshot rate as a multiple of the loop rate @@ -304,7 +318,7 @@ public: setup serial led output for a given channel number, with the given max number of LEDs in the chain. */ - virtual bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint16_t clock_mask = 0) { return false; } + virtual bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) { return false; } /* setup serial led output data for a given output channel