123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691 |
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/I2CDevice.h>
- #include <AP_BoardConfig/AP_BoardConfig.h>
- #include "OreoLED_I2C.h"
- #include "AP_Notify.h"
- #include <utility>
- #define OREOLED_BASE_I2C_ADDR 0x68
- #define OREOLED_BACKLEFT 0
- #define OREOLED_BACKRIGHT 1
- #define OREOLED_FRONTRIGHT 2
- #define OREOLED_FRONTLEFT 3
- #define PERIOD_SLOW 800
- #define PERIOD_FAST 500
- #define PERIOD_SUPER 150
- #define PO_ALTERNATE 180
- #define OREOLED_BOOT_CMD_BOOT_APP 0x60
- #define OREOLED_BOOT_CMD_BOOT_NONCE 0xA2
- extern const AP_HAL::HAL& hal;
- OreoLED_I2C::OreoLED_I2C(uint8_t bus, uint8_t theme):
- NotifyDevice(),
- _bus(bus),
- _oreo_theme(theme)
- {
- }
- bool OreoLED_I2C::init()
- {
-
- _dev = std::move(hal.i2c_mgr->get_device(_bus, OREOLED_BASE_I2C_ADDR));
- if (!_dev) {
- return false;
- }
-
- _dev->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&OreoLED_I2C::update_timer, void));
-
- return true;
- }
- void OreoLED_I2C::update()
- {
- if (slow_counter()) {
- return;
- }
- if (mode_firmware_update()) {
- return;
- }
- if (mode_init()) {
- return;
- }
- if (mode_failsafe_radio()) {
- return;
- }
- set_standard_colors();
- if (mode_failsafe_batt()) {
- return;
- }
- if (_pattern_override) {
- return;
- }
- if (mode_auto_flight()) {
- return;
- }
- mode_pilot_flight();
- }
- bool OreoLED_I2C::slow_counter()
- {
- _slow_count++;
- if (_slow_count < 5) {
- return true;
- } else {
- _slow_count = 0;
- return false;
- }
- }
- bool OreoLED_I2C::mode_firmware_update()
- {
- if (AP_Notify::flags.firmware_update) {
- set_macro(OREOLED_INSTANCE_ALL, OREOLED_PARAM_MACRO_COLOUR_CYCLE);
- return true;
- } else {
- return false;
- }
- }
- bool OreoLED_I2C::mode_init()
- {
- if (AP_Notify::flags.initialising) {
- set_rgb(OREOLED_INSTANCE_ALL, OREOLED_PATTERN_STROBE, 0, 0, 255,0,0,0,PERIOD_SUPER,0);
- return true;
- } else {
- return false;
- }
- }
- bool OreoLED_I2C::mode_failsafe_radio()
- {
- if (AP_Notify::flags.failsafe_radio) {
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SLOW,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SLOW,PO_ALTERNATE);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SLOW,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SLOW,0);
- }
- return AP_Notify::flags.failsafe_radio;
- }
- bool OreoLED_I2C::set_standard_colors()
- {
- if (!(AP_Notify::flags.gps_fusion)) {
- _rear_color_r = 255;
- _rear_color_g = 50;
- _rear_color_b = 0;
- return true;
- } else if (AP_Notify::flags.ekf_bad) {
- _rear_color_r = 255;
- _rear_color_g = 0;
- _rear_color_b = 255;
- return true;
- } else {
- _rear_color_r = 255;
- _rear_color_g = 255;
- _rear_color_b = 255;
- return false;
- }
- }
- bool OreoLED_I2C::mode_failsafe_batt()
- {
- if (AP_Notify::flags.failsafe_battery) {
- switch (_oreo_theme) {
- case OreoLED_Aircraft:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 0, 255, 0,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- break;
- case OreoLED_Automobile:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- break;
- default:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- break;
- }
- }
- return AP_Notify::flags.failsafe_battery;
- }
- bool OreoLED_I2C::mode_auto_flight()
- {
- switch (_oreo_theme) {
- case OreoLED_Aircraft:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SUPER,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 0, 255, 0,0,0,0,PERIOD_SUPER,0);
- if ((AP_Notify::flags.pre_arm_check && AP_Notify::flags.pre_arm_gps_check) || AP_Notify::flags.armed) {
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- } else {
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_SOLID, _rear_color_r, _rear_color_g, _rear_color_b);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_SOLID, _rear_color_r, _rear_color_g, _rear_color_b);
- }
- break;
- case OreoLED_Automobile:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_SUPER,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_SUPER,0);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- break;
- default:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_SUPER,0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_STROBE, 255, 255, 255,0,0,0,PERIOD_SUPER,0);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, 255, 0, 0,0,0,0,PERIOD_SUPER,PO_ALTERNATE);
- break;
- }
- return AP_Notify::flags.autopilot_mode;
- }
- bool OreoLED_I2C::mode_pilot_flight()
- {
- switch (_oreo_theme) {
- case OreoLED_Aircraft:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_SOLID, 255, 0, 0);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_SOLID, 0, 255, 0);
- if ((AP_Notify::flags.pre_arm_check && AP_Notify::flags.pre_arm_gps_check) || AP_Notify::flags.armed) {
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_FAST,0);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_STROBE, _rear_color_r, _rear_color_g, _rear_color_b,0,0,0,PERIOD_FAST,PO_ALTERNATE);
- } else {
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_SOLID, _rear_color_r, _rear_color_g, _rear_color_b);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_SOLID, _rear_color_r, _rear_color_g, _rear_color_b);
- }
- break;
- case OreoLED_Automobile:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_SOLID, 255, 255, 255);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_SOLID, 255, 255, 255);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_SOLID, 255, 0, 0);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_SOLID, 255, 0, 0);
- break;
- default:
- set_rgb(OREOLED_FRONTLEFT, OREOLED_PATTERN_SOLID, 255, 255, 255);
- set_rgb(OREOLED_FRONTRIGHT, OREOLED_PATTERN_SOLID, 255, 255, 255);
- set_rgb(OREOLED_BACKLEFT, OREOLED_PATTERN_SOLID, 255, 0, 0);
- set_rgb(OREOLED_BACKRIGHT, OREOLED_PATTERN_SOLID, 255, 0, 0);
- break;
- }
- return true;
- }
- void OreoLED_I2C::set_rgb(uint8_t instance, uint8_t red, uint8_t green, uint8_t blue)
- {
- set_rgb(instance, OREOLED_PATTERN_SOLID, red, green, blue);
- }
- void OreoLED_I2C::set_rgb(uint8_t instance, oreoled_pattern pattern, uint8_t red, uint8_t green, uint8_t blue)
- {
-
- WITH_SEMAPHORE(_sem);
-
- if (instance == OREOLED_INSTANCE_ALL) {
-
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
- _state_desired[i].set_rgb(pattern, red, green, blue);
- if (!(_state_desired[i] == _state_sent[i])) {
- _send_required = true;
- }
- }
- } else if (instance < OREOLED_NUM_LEDS) {
-
- _state_desired[instance].set_rgb(pattern, red, green, blue);
- if (!(_state_desired[instance] == _state_sent[instance])) {
- _send_required = true;
- }
- }
- }
- void OreoLED_I2C::set_rgb(uint8_t instance, oreoled_pattern pattern, uint8_t red, uint8_t green, uint8_t blue,
- uint8_t amplitude_red, uint8_t amplitude_green, uint8_t amplitude_blue,
- uint16_t period, uint16_t phase_offset)
- {
- WITH_SEMAPHORE(_sem);
-
- if (instance == OREOLED_INSTANCE_ALL) {
-
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
- _state_desired[i].set_rgb(pattern, red, green, blue, amplitude_red, amplitude_green, amplitude_blue, period, phase_offset);
- if (!(_state_desired[i] == _state_sent[i])) {
- _send_required = true;
- }
- }
- } else if (instance < OREOLED_NUM_LEDS) {
-
- _state_desired[instance].set_rgb(pattern, red, green, blue, amplitude_red, amplitude_green, amplitude_blue, period, phase_offset);
- if (!(_state_desired[instance] == _state_sent[instance])) {
- _send_required = true;
- }
- }
- }
- void OreoLED_I2C::set_macro(uint8_t instance, oreoled_macro macro)
- {
- WITH_SEMAPHORE(_sem);
-
- if (instance == OREOLED_INSTANCE_ALL) {
-
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
- _state_desired[i].set_macro(macro);
- if (!(_state_desired[i] == _state_sent[i])) {
- _send_required = true;
- }
- }
- } else if (instance < OREOLED_NUM_LEDS) {
-
- _state_desired[instance].set_macro(macro);
- if (!(_state_desired[instance] == _state_sent[instance])) {
- _send_required = true;
- }
- }
- }
- void OreoLED_I2C::clear_state(void)
- {
- WITH_SEMAPHORE(_sem);
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
- _state_desired[i].clear_state();
- }
- _send_required = false;
- }
- bool OreoLED_I2C::command_send(oreoled_cmd_t &cmd)
- {
-
- _dev->set_address(OREOLED_BASE_I2C_ADDR + cmd.led_num);
-
- uint8_t cmd_xor = OREOLED_BASE_I2C_ADDR + cmd.led_num;
- for (uint8_t i = 0; i < cmd.num_bytes; i++) {
- cmd_xor ^= cmd.buff[i];
- }
- cmd.buff[cmd.num_bytes++] = cmd_xor;
- uint8_t reply[3] {};
- bool ret = _dev->transfer(cmd.buff, cmd.num_bytes, reply, sizeof(reply));
-
- return ret;
- }
- void OreoLED_I2C::boot_leds(void)
- {
- oreoled_cmd_t cmd;
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
- cmd.led_num = i;
- cmd.buff[0] = OREOLED_BOOT_CMD_BOOT_APP;
- cmd.buff[1] = OREOLED_BOOT_CMD_BOOT_NONCE;
- cmd.buff[2] = OREOLED_BASE_I2C_ADDR + i;
- cmd.num_bytes = 3;
- command_send(cmd);
- }
- }
- void OreoLED_I2C::update_timer(void)
- {
- WITH_SEMAPHORE(_sem);
- uint32_t now = AP_HAL::millis();
- if (_boot_count < 20 &&
- now - _last_boot_ms > 100) {
-
- _boot_count++;
- _last_boot_ms = now;
- boot_leds();
- }
-
-
-
-
-
- if (now - _last_sync_ms > 4100) {
- _last_sync_ms = now;
- send_sync();
- }
-
- if (!_send_required) {
- return;
- }
-
- for (uint8_t i=0; i<OREOLED_NUM_LEDS; i++) {
-
- if (true) {
- switch (_state_desired[i].mode) {
- case OREOLED_MODE_MACRO: {
- oreoled_cmd_t cmd {};
- cmd.led_num = i;
- cmd.buff[0] = OREOLED_PATTERN_PARAMUPDATE;
- cmd.buff[1] = OREOLED_PARAM_MACRO;
- cmd.buff[2] = _state_desired[i].macro;
- cmd.num_bytes = 3;
- command_send(cmd);
- break;
- }
- case OREOLED_MODE_RGB: {
- oreoled_cmd_t cmd {};
- cmd.led_num = i;
- cmd.buff[0] = _state_desired[i].pattern;
- cmd.buff[1] = OREOLED_PARAM_BIAS_RED;
- cmd.buff[2] = _state_desired[i].red;
- cmd.buff[3] = OREOLED_PARAM_BIAS_GREEN;
- cmd.buff[4] = _state_desired[i].green;
- cmd.buff[5] = OREOLED_PARAM_BIAS_BLUE;
- cmd.buff[6] = _state_desired[i].blue;
- cmd.num_bytes = 7;
- command_send(cmd);
- break;
- }
- case OREOLED_MODE_RGB_EXTENDED: {
- oreoled_cmd_t cmd {};
- cmd.led_num = i;
- cmd.buff[0] = _state_desired[i].pattern;
- cmd.buff[1] = OREOLED_PARAM_BIAS_RED;
- cmd.buff[2] = _state_desired[i].red;
- cmd.buff[3] = OREOLED_PARAM_BIAS_GREEN;
- cmd.buff[4] = _state_desired[i].green;
- cmd.buff[5] = OREOLED_PARAM_BIAS_BLUE;
- cmd.buff[6] = _state_desired[i].blue;
- cmd.buff[7] = OREOLED_PARAM_AMPLITUDE_RED;
- cmd.buff[8] = _state_desired[i].amplitude_red;
- cmd.buff[9] = OREOLED_PARAM_AMPLITUDE_GREEN;
- cmd.buff[10] = _state_desired[i].amplitude_green;
- cmd.buff[11] = OREOLED_PARAM_AMPLITUDE_BLUE;
- cmd.buff[12] = _state_desired[i].amplitude_blue;
-
-
- cmd.buff[13] = OREOLED_PARAM_PERIOD;
- cmd.buff[14] = (_state_desired[i].period & 0xFF00) >> 8;
- cmd.buff[15] = (_state_desired[i].period & 0x00FF);
- cmd.buff[16] = OREOLED_PARAM_PHASEOFFSET;
- cmd.buff[17] = (_state_desired[i].phase_offset & 0xFF00) >> 8;
- cmd.buff[18] = (_state_desired[i].phase_offset & 0x00FF);
- cmd.num_bytes = 19;
- command_send(cmd);
- break;
- }
- default:
- break;
- };
-
- _state_sent[i] = _state_desired[i];
- }
- }
-
- _send_required = false;
- }
- void OreoLED_I2C::send_sync(void)
- {
-
- _dev->set_address(0);
-
- uint8_t msg[] = {0x01, 0x00};
-
- _dev->set_retries(0);
- _dev->transfer(msg, sizeof(msg), nullptr, 0);
- _dev->set_retries(2);
- }
- void OreoLED_I2C::handle_led_control(const mavlink_message_t &msg)
- {
-
- mavlink_led_control_t packet;
- mavlink_msg_led_control_decode(&msg, &packet);
-
- if (packet.instance >= OREOLED_NUM_LEDS && packet.instance != OREOLED_INSTANCE_ALL) {
- return;
- }
-
- if (packet.pattern == LED_CONTROL_PATTERN_OFF) {
- _pattern_override = 0;
- clear_state();
- return;
- }
- if (packet.pattern == LED_CONTROL_PATTERN_CUSTOM) {
-
-
-
-
- if (packet.custom_len < CUSTOM_HEADER_LENGTH) {
- return;
- }
-
- if (memcmp(packet.custom_bytes, "RGB0", CUSTOM_HEADER_LENGTH) == 0) {
-
- if (packet.custom_len != CUSTOM_HEADER_LENGTH + 4) {
- return;
- }
-
- if (packet.custom_bytes[CUSTOM_HEADER_LENGTH] >= OREOLED_PATTERN_ENUM_COUNT) {
- return;
- }
-
- oreoled_pattern pattern = (oreoled_pattern)packet.custom_bytes[CUSTOM_HEADER_LENGTH];
-
- set_rgb(packet.instance, pattern, packet.custom_bytes[CUSTOM_HEADER_LENGTH + 1], packet.custom_bytes[CUSTOM_HEADER_LENGTH + 2], packet.custom_bytes[CUSTOM_HEADER_LENGTH + 3]);
- } else if (memcmp(packet.custom_bytes, "RGB1", CUSTOM_HEADER_LENGTH) == 0) {
-
- if (packet.custom_len != CUSTOM_HEADER_LENGTH + 11) {
- return;
- }
-
- if (packet.custom_bytes[CUSTOM_HEADER_LENGTH] >= OREOLED_PATTERN_ENUM_COUNT) {
- return;
- }
-
- oreoled_pattern pattern = (oreoled_pattern)packet.custom_bytes[CUSTOM_HEADER_LENGTH];
-
-
- uint16_t period =
- ((0x00FF & (uint16_t)packet.custom_bytes[CUSTOM_HEADER_LENGTH + 7]) << 8) |
- (0x00FF & (uint16_t)packet.custom_bytes[CUSTOM_HEADER_LENGTH + 8]);
- uint16_t phase_offset =
- ((0x00FF & (uint16_t)packet.custom_bytes[CUSTOM_HEADER_LENGTH + 9]) << 8) |
- (0x00FF & (uint16_t)packet.custom_bytes[CUSTOM_HEADER_LENGTH + 10]);
-
- set_rgb(packet.instance, pattern, packet.custom_bytes[CUSTOM_HEADER_LENGTH + 1], packet.custom_bytes[CUSTOM_HEADER_LENGTH + 2],
- packet.custom_bytes[CUSTOM_HEADER_LENGTH + 3], packet.custom_bytes[CUSTOM_HEADER_LENGTH + 4], packet.custom_bytes[CUSTOM_HEADER_LENGTH + 5],
- packet.custom_bytes[CUSTOM_HEADER_LENGTH + 6], period, phase_offset);
- } else {
- return;
- }
- } else {
-
- set_macro(packet.instance, (oreoled_macro)packet.pattern);
- }
- _pattern_override = packet.pattern;
- }
- OreoLED_I2C::oreo_state::oreo_state()
- {
- clear_state();
- }
- void OreoLED_I2C::oreo_state::clear_state()
- {
- mode = OREOLED_MODE_NONE;
- pattern = OREOLED_PATTERN_OFF;
- macro = OREOLED_PARAM_MACRO_RESET;
- red = 0;
- green = 0;
- blue = 0;
- amplitude_red = 0;
- amplitude_green = 0;
- amplitude_blue = 0;
- period = 0;
- repeat = 0;
- phase_offset = 0;
- }
- void OreoLED_I2C::oreo_state::set_macro(oreoled_macro new_macro)
- {
- clear_state();
- mode = OREOLED_MODE_MACRO;
- macro = new_macro;
- }
- void OreoLED_I2C::oreo_state::set_rgb(enum oreoled_pattern new_pattern, uint8_t new_red, uint8_t new_green, uint8_t new_blue)
- {
- clear_state();
- mode = OREOLED_MODE_RGB;
- pattern = new_pattern;
- red = new_red;
- green = new_green;
- blue = new_blue;
- }
- void OreoLED_I2C::oreo_state::set_rgb(enum oreoled_pattern new_pattern, uint8_t new_red, uint8_t new_green,
- uint8_t new_blue, uint8_t new_amplitude_red, uint8_t new_amplitude_green, uint8_t new_amplitude_blue,
- uint16_t new_period, uint16_t new_phase_offset)
- {
- clear_state();
- mode = OREOLED_MODE_RGB_EXTENDED;
- pattern = new_pattern;
- red = new_red;
- green = new_green;
- blue = new_blue;
- amplitude_red = new_amplitude_red;
- amplitude_green = new_amplitude_green;
- amplitude_blue = new_amplitude_blue;
- period = new_period;
- phase_offset = new_phase_offset;
- }
- bool OreoLED_I2C::oreo_state::operator==(const OreoLED_I2C::oreo_state &os)
- {
- return ((os.mode==mode) && (os.pattern==pattern) && (os.macro==macro) && (os.red==red) && (os.green==green) && (os.blue==blue)
- && (os.amplitude_red==amplitude_red) && (os.amplitude_green==amplitude_green) && (os.amplitude_blue==amplitude_blue)
- && (os.period==period) && (os.repeat==repeat) && (os.phase_offset==phase_offset));
- }
|