AP_HAL: support ProfiLEDs

This commit is contained in:
Peter Hall 2020-02-22 23:55:21 +00:00 committed by Randy Mackay
parent fa1b8cb792
commit a42b459b27
2 changed files with 10 additions and 7 deletions

View File

@ -27,6 +27,8 @@ const char* AP_HAL::RCOutput::get_output_mode_string(enum output_mode out_mode)
return "DS1200"; return "DS1200";
case MODE_NEOPIXEL: case MODE_NEOPIXEL:
return "NeoP"; return "NeoP";
case MODE_PROFILED:
return "ProfiLED";
} }
// we should never reach here but just in case // we should never reach here but just in case

View File

@ -179,6 +179,7 @@ public:
MODE_PWM_DSHOT600, MODE_PWM_DSHOT600,
MODE_PWM_DSHOT1200, MODE_PWM_DSHOT1200,
MODE_NEOPIXEL, // same as MODE_PWM_DSHOT at 800kHz but it's an LED MODE_NEOPIXEL, // same as MODE_PWM_DSHOT at 800kHz but it's an LED
MODE_PROFILED, // same as MODE_PWM_DSHOT using separate clock and data
}; };
virtual void set_output_mode(uint16_t mask, enum output_mode mode) {} virtual void set_output_mode(uint16_t mask, enum output_mode mode) {}
@ -199,21 +200,21 @@ public:
virtual void set_telem_request_mask(uint16_t mask) {} virtual void set_telem_request_mask(uint16_t mask) {}
/* /*
setup neopixel (WS2812B) output for a given channel number, with setup serial led output for a given channel number, with
the given max number of LEDs in the chain. the given max number of LEDs in the chain.
*/ */
virtual bool set_neopixel_num_LEDs(const uint16_t chan, uint8_t num_leds) { return false; } 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; }
/* /*
setup neopixel (WS2812B) output data for a given output channel setup serial led output data for a given output channel
and led number. A led number of -1 means all LEDs. LED 0 is the first LED and led number. A led number of -1 means all LEDs. LED 0 is the first LED
*/ */
virtual void set_neopixel_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) {} virtual void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) {}
/* /*
trigger send of neopixel data trigger send of serial led
*/ */
virtual void neopixel_send(void) {} virtual void serial_led_send(const uint16_t chan) {}
protected: protected: