diff --git a/README.md b/README.md index c2a6594..474daf2 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,24 @@ +### PROGRAM FLOW +Screens available: +1. Introductions Screen + - Just the logo or some cool graphics +2. Controller Screen + - Showing the buttons states and gimbal positions + - I2C Rates, Battery health, Gimbal Rate +3. Gimbal Trims - Throttle, Yaw +4. Gimbal Trims - Pitch, Roll +5. Settings +6. About +The Introduction screen will only appear once. + + + + + + + +### Pin Layouts +-----------------------+ | O | USB | O | diff --git a/src/.main.cpp.swp b/src/.main.cpp.swp index 4ee3063..fdae3af 100644 Binary files a/src/.main.cpp.swp and b/src/.main.cpp.swp differ diff --git a/src/.main.h.swp b/src/.main.h.swp index eab0eea..bceabeb 100644 Binary files a/src/.main.h.swp and b/src/.main.h.swp differ diff --git a/src/battery_icons.h b/src/battery_icons.h new file mode 100644 index 0000000..5e030c6 --- /dev/null +++ b/src/battery_icons.h @@ -0,0 +1,91 @@ +#define batt_100_width 32 +#define batt_100_height 16 + +const uint8_t batt_100_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0xff, 0xff, 0x2f, + 0xfd, 0xff, 0xff, 0x2f, 0xfd, 0xff, 0xff, 0x2f, 0xfd, 0xff, 0xff, 0xef, + 0xfd, 0xff, 0xff, 0xef, 0xfd, 0xff, 0xff, 0xef, 0xfd, 0xff, 0xff, 0xef, + 0xfd, 0xff, 0xff, 0xef, 0xfd, 0xff, 0xff, 0xef, 0xfd, 0xff, 0xff, 0x2f, + 0xfd, 0xff, 0xff, 0x2f, 0xfd, 0xff, 0xff, 0x2f, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_87_width 32 +#define batt_87_height 16 +const uint8_t batt_87_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0xff, 0xff, 0x20, + 0xfd, 0xff, 0xff, 0x20, 0xfd, 0xff, 0xff, 0x20, 0xfd, 0xff, 0xff, 0xe0, + 0xfd, 0xff, 0xff, 0xe0, 0xfd, 0xff, 0xff, 0xe0, 0xfd, 0xff, 0xff, 0xe0, + 0xfd, 0xff, 0xff, 0xe0, 0xfd, 0xff, 0xff, 0xe0, 0xfd, 0xff, 0xff, 0x20, + 0xfd, 0xff, 0xff, 0x20, 0xfd, 0xff, 0xff, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_75_width 32 +#define batt_75_height 16 +const uint8_t batt_75_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0xff, 0x1f, 0x20, + 0xfd, 0xff, 0x1f, 0x20, 0xfd, 0xff, 0x1f, 0x20, 0xfd, 0xff, 0x1f, 0xe0, + 0xfd, 0xff, 0x1f, 0xe0, 0xfd, 0xff, 0x1f, 0xe0, 0xfd, 0xff, 0x1f, 0xe0, + 0xfd, 0xff, 0x1f, 0xe0, 0xfd, 0xff, 0x1f, 0xe0, 0xfd, 0xff, 0x1f, 0x20, + 0xfd, 0xff, 0x1f, 0x20, 0xfd, 0xff, 0x1f, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_62_width 32 +#define batt_62_height 16 +const uint8_t batt_62_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0xff, 0x03, 0x20, + 0xfd, 0xff, 0x03, 0x20, 0xfd, 0xff, 0x03, 0x20, 0xfd, 0xff, 0x03, 0xe0, + 0xfd, 0xff, 0x03, 0xe0, 0xfd, 0xff, 0x03, 0xe0, 0xfd, 0xff, 0x03, 0xe0, + 0xfd, 0xff, 0x03, 0xe0, 0xfd, 0xff, 0x03, 0xe0, 0xfd, 0xff, 0x03, 0x20, + 0xfd, 0xff, 0x03, 0x20, 0xfd, 0xff, 0x03, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_50_width 32 +#define batt_50_height 16 +const uint8_t batt_50_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0x7f, 0x00, 0x20, + 0xfd, 0x7f, 0x00, 0x20, 0xfd, 0x7f, 0x00, 0x20, 0xfd, 0x7f, 0x00, 0xe0, + 0xfd, 0x7f, 0x00, 0xe0, 0xfd, 0x7f, 0x00, 0xe0, 0xfd, 0x7f, 0x00, 0xe0, + 0xfd, 0x7f, 0x00, 0xe0, 0xfd, 0x7f, 0x00, 0xe0, 0xfd, 0x7f, 0x00, 0x20, + 0xfd, 0x7f, 0x00, 0x20, 0xfd, 0x7f, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_37_width 32 +#define batt_37_height 16 +const uint8_t batt_37_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0x07, 0x00, 0x20, + 0xfd, 0x07, 0x00, 0x20, 0xfd, 0x07, 0x00, 0x20, 0xfd, 0x07, 0x00, 0xe0, + 0xfd, 0x07, 0x00, 0xe0, 0xfd, 0x07, 0x00, 0xe0, 0xfd, 0x07, 0x00, 0xe0, + 0xfd, 0x07, 0x00, 0xe0, 0xfd, 0x07, 0x00, 0xe0, 0xfd, 0x07, 0x00, 0x20, + 0xfd, 0x07, 0x00, 0x20, 0xfd, 0x07, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_25_width 32 +#define batt_25_height 16 +const uint8_t batt_25_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0xfd, 0x00, 0x00, 0x20, + 0xfd, 0x00, 0x00, 0x20, 0xfd, 0x00, 0x00, 0x20, 0xfd, 0x00, 0x00, 0xe0, + 0xfd, 0x00, 0x00, 0xe0, 0xfd, 0x00, 0x00, 0xe0, 0xfd, 0x00, 0x00, 0xe0, + 0xfd, 0x00, 0x00, 0xe0, 0xfd, 0x00, 0x00, 0xe0, 0xfd, 0x00, 0x00, 0x20, + 0xfd, 0x00, 0x00, 0x20, 0xfd, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_12_width 32 +#define batt_12_height 16 +const uint8_t batt_12_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0x1d, 0x00, 0x00, 0x20, + 0x1d, 0x00, 0x00, 0x20, 0x1d, 0x00, 0x00, 0x20, 0x1d, 0x00, 0x00, 0xe0, + 0x1d, 0x00, 0x00, 0xe0, 0x1d, 0x00, 0x00, 0xe0, 0x1d, 0x00, 0x00, 0xe0, + 0x1d, 0x00, 0x00, 0xe0, 0x1d, 0x00, 0x00, 0xe0, 0x1d, 0x00, 0x00, 0x20, + 0x1d, 0x00, 0x00, 0x20, 0x1d, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + +#define batt_00_width 32 +#define batt_00_height 16 +const uint8_t batt_00_bits[] PROGMEM = { + 0xff, 0xff, 0xff, 0x3f, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0xe0, + 0x01, 0x00, 0x00, 0xe0, 0x01, 0x00, 0x00, 0xe0, 0x01, 0x00, 0x00, 0xe0, + 0x01, 0x00, 0x00, 0xe0, 0x01, 0x00, 0x00, 0xe0, 0x01, 0x00, 0x00, 0x20, + 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, 0x01, 0x00, 0x00, 0x20, + 0xff, 0xff, 0xff, 0x3f }; + diff --git a/src/bigrc-logo.h b/src/bigrc-logo.h new file mode 100644 index 0000000..e5fdb6b --- /dev/null +++ b/src/bigrc-logo.h @@ -0,0 +1,46 @@ +#define bigrc_logo_width 128 +#define bigrc_logo_height 30 + +const uint8_t bigrc_logo_bits[] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x46, 0x68, 0x00, + 0x40, 0x01, 0x00, 0x44, 0x08, 0x88, 0x46, 0x08, 0x00, 0x00, 0x68, 0x04, + 0xC0, 0xFF, 0xFF, 0x0F, 0xF8, 0x03, 0xC0, 0xFF, 0x1F, 0xFE, 0xFF, 0x3F, + 0x00, 0xE0, 0xFF, 0x1F, 0xC0, 0xFF, 0xFF, 0x0F, 0xF8, 0x07, 0xF8, 0xFF, + 0x1F, 0xFE, 0xFF, 0x7F, 0x00, 0xF8, 0xFF, 0x1F, 0xC0, 0xFF, 0xFF, 0x1F, + 0xF8, 0x03, 0xFE, 0xFF, 0x3F, 0xFF, 0xFF, 0xFF, 0x00, 0xFE, 0xFF, 0x0F, + 0xC0, 0xFF, 0xFF, 0x1F, 0xFC, 0x03, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0xFF, + 0x00, 0xFF, 0xFF, 0x0F, 0xC0, 0xFF, 0xFF, 0x3F, 0xFC, 0x83, 0xFF, 0xFF, + 0x0F, 0xFF, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0x0F, 0xE0, 0xD6, 0xFE, 0x1F, + 0xFC, 0xC3, 0xFF, 0xD7, 0x0E, 0xB6, 0xDD, 0xFF, 0xE1, 0xFF, 0xBB, 0x07, + 0x00, 0x00, 0xC0, 0x3F, 0xFC, 0xC1, 0x3F, 0x00, 0x00, 0x00, 0x00, 0xFF, + 0xC0, 0x3F, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x1F, 0xFE, 0xE1, 0x3F, 0x00, + 0x00, 0x00, 0x00, 0xFE, 0xF0, 0x1F, 0x00, 0x00, 0xE0, 0xFF, 0xFB, 0x0F, + 0xFE, 0xF0, 0x0F, 0xFE, 0x83, 0x1F, 0x00, 0xFE, 0xF0, 0x0F, 0x00, 0x00, + 0xF0, 0xFF, 0xFF, 0x0F, 0xFE, 0xF1, 0x07, 0xFF, 0x87, 0xBF, 0x80, 0xFF, + 0xF0, 0x07, 0x00, 0x00, 0xF0, 0xFF, 0xFF, 0x07, 0xFE, 0xF0, 0x0F, 0xFF, + 0xC7, 0xFF, 0xFF, 0x7F, 0xF8, 0x07, 0x00, 0x00, 0xF0, 0xFF, 0xFF, 0x07, + 0xFF, 0xF8, 0x07, 0xFF, 0xC7, 0xFF, 0xFF, 0x3F, 0xF8, 0x03, 0x00, 0x00, + 0xF8, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, 0x03, 0xFF, 0xC3, 0xFF, 0xFF, 0x3F, + 0xFC, 0x07, 0x00, 0x00, 0xF8, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, 0x07, 0xFF, + 0xC3, 0xFF, 0xFF, 0x0F, 0xFC, 0x03, 0x00, 0x00, 0xF8, 0x0B, 0xF0, 0x8F, + 0x7F, 0xF8, 0x07, 0xFC, 0xE3, 0xFF, 0xFF, 0x07, 0xF8, 0x07, 0x00, 0x00, + 0xF8, 0x03, 0xF0, 0x87, 0x7F, 0xF8, 0x0F, 0xFC, 0xE3, 0xFF, 0xFF, 0x03, + 0xFC, 0x0F, 0x00, 0x00, 0xFC, 0x67, 0xFD, 0x8F, 0x3F, 0xF8, 0x7F, 0xFE, + 0xE1, 0x0F, 0xFE, 0x03, 0xF8, 0x5F, 0x44, 0x00, 0xFC, 0xFF, 0xFF, 0x87, + 0x3F, 0xF8, 0xFF, 0xFF, 0xF3, 0x0F, 0xFE, 0x03, 0xF8, 0xFF, 0xFF, 0x01, + 0xFC, 0xFF, 0xFF, 0xC3, 0x3F, 0xF0, 0xFF, 0xFF, 0xE1, 0x0F, 0xF8, 0x07, + 0xF0, 0xFF, 0xFF, 0x00, 0xFC, 0xFF, 0xFF, 0xC3, 0x3F, 0xE0, 0xFF, 0xFF, + 0xF0, 0x0F, 0xF8, 0x07, 0xF0, 0xFF, 0xFF, 0x00, 0xFE, 0xFF, 0xFF, 0xC0, + 0x1F, 0xE0, 0xFF, 0xFF, 0xF0, 0x07, 0xF8, 0x0F, 0xE0, 0xFF, 0xFF, 0x00, + 0xFE, 0xFF, 0x7F, 0xC0, 0x1F, 0x80, 0xFF, 0xFF, 0xF1, 0x07, 0xF0, 0x0F, + 0xC0, 0xFF, 0xFF, 0x00, 0xB8, 0xAE, 0x0B, 0x80, 0x1E, 0x00, 0xB9, 0xAE, + 0xE0, 0x05, 0xE0, 0x1F, 0x00, 0xB9, 0x6D, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x1F, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x3F, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xC0, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x7F, 0x00, 0x00, 0x00, 0x00, + }; + diff --git a/src/main.cpp b/src/main.cpp index b5cc812..b8ee824 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -45,8 +45,8 @@ void setup() { display.init(); display.setContrast(255); display.setTextAlignment(TEXT_ALIGN_LEFT); - display.setFont(ArialMT_Plain_24); - display.drawString(0, 16, "BigRC v1.0"); + display.setFont(ArialMT_Plain_10); + display.drawString(0, 0, "Booting up..."); display.display(); // Init ADC @@ -364,6 +364,9 @@ void taskDisplay(void *pvParameters) { // Delay for about 1.5 seconds before starting. So the intro screen still there for a while. delay(1500); + // Only for initial + intro_screen_start = millis(); + for(;;) { vTaskDelay(10); @@ -381,10 +384,12 @@ void taskDisplay(void *pvParameters) { } else if(counter > 0) { pulse_ms = 250; } - + + /*** char msg[64]; sprintf(msg, "I2C Packets: %d Gimbal Rate: %d\r\n", i2c_counter, profile_gimbal_rate); Serial.print(msg); + ***/ /*** // sprintf(msg, "Total Packets: %d Pulse: %d SBUS: %i", counter, pulse_ms, sbus.sbus_packets_sent); @@ -395,7 +400,9 @@ void taskDisplay(void *pvParameters) { last_display = millis(); } - display_info(); + // display_info(); + + show_display(); } } @@ -415,13 +422,13 @@ void taskGimbal(void *pvParameters) { // throttle_steps = median_throttle(raw_throttle); // Sampling throttle // throttle_steps = sampling(THROTTLE_POOL); - throttle_steps = ADS.readADC(3); + throttle_steps = ADS.readADC(3) * -1; // raw_yaw = analogRead(YAW_PIN); // yaw_steps = median_yaw(raw_yaw); // Sampling yaw // yaw_steps = sampling(YAW_POOL); - yaw_steps = ADS.readADC(2); + yaw_steps = ADS.readADC(2) * -1; // raw_roll = analogRead(ROLL_PIN); // roll_steps = median_roll(raw_roll); @@ -487,6 +494,7 @@ void taskButton(void *pvParameters) { (void) pvParameters; uint32_t last_check = 0; uint32_t last_toggle = 0; + uint32_t last_combo = 0; bool toggled = false; for(;;) { @@ -506,36 +514,56 @@ void taskButton(void *pvParameters) { button9 = ((GPIO.in >> BUTTON9) & 0x1) ? 0 : 1; // E button10 = ((GPIO.in >> BUTTON10) & 0x1) ? 0 : 1; // F + // Processing toggle buttons if((uint32_t)(millis() - last_toggle) > 250) { - if(button3) { - toggle_buttons[TOGGLE_A] = !toggle_buttons[TOGGLE_A]; - toggled = true; - } - - if(button4) { - toggle_buttons[TOGGLE_B] = !toggle_buttons[TOGGLE_B]; - toggled = true; - } - - if(button5) { - toggle_buttons[TOGGLE_C] = !toggle_buttons[TOGGLE_C]; - toggled = true; - } - - if(button8) { - toggle_buttons[TOGGLE_D] = !toggle_buttons[TOGGLE_D]; - toggled = true; - } - - if(button9) { - toggle_buttons[TOGGLE_E] = !toggle_buttons[TOGGLE_E]; - toggled = true; + if((uint32_t)(millis() - last_combo) > 250) { + if(button2 && button7) { // CANCEL + DOWN (COMBO BUTTON to switch to another page) + current_screen++; + + // RESET to 1 screen + if(current_screen >= screen_length) + current_screen = SCREEN_CONTROLLER; + + // Making sure not being used by others + button2 = 0; + button7 = 0; + // Only process this on next expired time + last_combo = millis(); + } } - - if(button10) { - toggle_buttons[TOGGLE_F] = !toggle_buttons[TOGGLE_F]; - toggled = true; + + // The Toggle only works when is active + if(current_screen == SCREEN_CONTROLLER) { + if(button3) { + toggle_buttons[TOGGLE_A] = !toggle_buttons[TOGGLE_A]; + toggled = true; + } + + if(button4) { + toggle_buttons[TOGGLE_B] = !toggle_buttons[TOGGLE_B]; + toggled = true; + } + + if(button5) { + toggle_buttons[TOGGLE_C] = !toggle_buttons[TOGGLE_C]; + toggled = true; + } + + if(button8) { + toggle_buttons[TOGGLE_D] = !toggle_buttons[TOGGLE_D]; + toggled = true; + } + + if(button9) { + toggle_buttons[TOGGLE_E] = !toggle_buttons[TOGGLE_E]; + toggled = true; + } + + if(button10) { + toggle_buttons[TOGGLE_F] = !toggle_buttons[TOGGLE_F]; + toggled = true; + } } if(toggled) { @@ -555,6 +583,8 @@ void taskButton(void *pvParameters) { min_throttle = throttle_steps; } + throttle_val = map(throttle_steps, min_throttle, max_throttle, 1000, 2000) - trim_throttle; + /** throttle_val_tmp = map(throttle_steps, min_throttle, max_throttle, 1000, 2000); if(throttle_val - throttle_val_tmp > RC_DEADBAND) { throttle_val = throttle_val_tmp; @@ -563,7 +593,7 @@ void taskButton(void *pvParameters) { throttle_val = throttle_val_tmp; } } - + **/ sbusData.ch[1] = throttle_val; //// sbus.rcCommand[YAW] = incomingReadings.yaw; @@ -573,6 +603,8 @@ void taskButton(void *pvParameters) { min_yaw = yaw_steps; } + yaw_val = map(yaw_steps, min_yaw, max_yaw, 1000, 2000) + trim_yaw; + /** yaw_val_tmp = map(yaw_steps, min_yaw, max_yaw, 1000, 2000); if(yaw_val - yaw_val_tmp > RC_DEADBAND) { yaw_val = yaw_val_tmp; @@ -581,6 +613,7 @@ void taskButton(void *pvParameters) { yaw_val = yaw_val_tmp; } } + **/ sbusData.ch[0] = yaw_val; //// sbus.rcCommand[PITCH] = incomingReadings.pitch; @@ -590,6 +623,8 @@ void taskButton(void *pvParameters) { min_pitch = pitch_steps; } + pitch_val = map(pitch_steps, min_pitch, max_pitch, 1000, 2000) + trim_pitch; + /** pitch_val_tmp = map(pitch_steps, min_pitch, max_pitch, 1000, 2000); if(pitch_val - pitch_val_tmp > RC_DEADBAND) { pitch_val = pitch_val_tmp; @@ -598,6 +633,7 @@ void taskButton(void *pvParameters) { pitch_val = pitch_val_tmp; } } + **/ sbusData.ch[2] = pitch_val; //// sbus.rcCommand[ROLL] = incomingReadings.roll; @@ -607,6 +643,8 @@ void taskButton(void *pvParameters) { min_roll = roll_steps; } + roll_val = map(roll_steps, min_roll, max_roll, 1000, 2000) + trim_roll; + /** roll_val_tmp = map(roll_steps, min_roll, max_roll, 1000, 2000); if(roll_val - roll_val_tmp > RC_DEADBAND) { roll_val = roll_val_tmp; @@ -615,6 +653,7 @@ void taskButton(void *pvParameters) { roll_val = roll_val_tmp; } } + **/ sbusData.ch[3] = roll_val; sbusData.ch[4] = (toggle_buttons[TOGGLE_A] & 0x01) ? 2000 : 1000; // Toggle A @@ -994,6 +1033,517 @@ void onI2C0Receive(int len) { } +void screenIntro(void) { + display.drawXbm(0, 18, bigrc_logo_width, bigrc_logo_height, bigrc_logo_bits); +} + + +void show_rates(void) { + // Show Gimbal Rate + display.setTextAlignment(TEXT_ALIGN_RIGHT); + display.drawString(30, 54, String(profile_gimbal_rate) + "G"); + + // Show I2C Rate + display.setTextAlignment(TEXT_ALIGN_RIGHT); + display.drawString(128, 54, String(i2c_counter) + "R"); +} + + +void show_toggle_buttons(void) { + display.setColor(WHITE); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.drawRect(0, 0, 16, 16); + if(toggle_buttons[TOGGLE_A]) { + display.fillRect(2, 2, 12, 12); + display.setColor(BLACK); + display.drawString(8, 1, "A"); + } else { + display.setColor(WHITE); + display.drawString(8, 1, "A"); + } + + display.setColor(WHITE); + display.drawRect(0, 17, 16, 16); + if(toggle_buttons[TOGGLE_B]) { + display.fillRect(2, 19, 12, 12); + display.setColor(BLACK); + display.drawString(8, 18, "B"); + } else { + display.setColor(WHITE); + display.drawString(8, 18, "B"); + } + + display.setColor(WHITE); + display.drawRect(0, 34, 16, 16); + if(toggle_buttons[TOGGLE_C]) { + display.fillRect(2, 36, 12, 12); + display.setColor(BLACK); + display.drawString(7, 35, "C"); + } else { + display.setColor(WHITE); + display.drawString(7, 35, "C"); + } + + display.setColor(WHITE); + display.drawRect(112, 0, 16, 16); + if(toggle_buttons[TOGGLE_D]) { + display.fillRect(114, 2, 12, 12); + display.setColor(BLACK); + display.drawString(120, 2, "D"); + } else { + display.setColor(WHITE); + display.drawString(120, 2, "D"); + } + + display.setColor(WHITE); + display.drawRect(112, 17, 16, 16); + if(toggle_buttons[TOGGLE_E]) { + display.fillRect(114, 19, 12, 12); + display.setColor(BLACK); + display.drawString(120, 18, "E"); + } else { + display.setColor(WHITE); + display.drawString(120, 18, "E"); + } + + display.setColor(WHITE); + display.drawRect(112, 34, 16, 16); + if(toggle_buttons[TOGGLE_F]) { + display.fillRect(114, 36, 12, 12); + display.setColor(BLACK); + display.drawString(120, 35, "F"); + } else { + display.setColor(WHITE); + display.drawString(120, 35, "F"); + } + +/*** + if(toggle_buttons[TOGGLE_D]) { + display.setColor(WHITE); + display.fillRect(107, 0, 20, 20); + display.setColor(BLACK); + display.drawString(114, 2, "D"); + } else { + display.setColor(WHITE); + display.drawRect(107, 0, 20, 20); + display.drawString(114, 2, "D"); + } + + if(toggle_buttons[TOGGLE_E]) { + display.setColor(WHITE); + display.fillRect(107, 21, 20, 20); + display.setColor(BLACK); + display.drawString(114, 23, "E"); + } else { + display.setColor(WHITE); + display.drawRect(107, 21, 20, 20); + display.drawString(114, 23, "E"); + } + + if(toggle_buttons[TOGGLE_F]) { + display.setColor(WHITE); + display.fillRect(107, 42, 20, 20); + display.setColor(BLACK); + display.drawString(114, 44, "F"); + } else { + display.setColor(WHITE); + display.drawRect(107, 42, 20, 20); + display.drawString(114, 44, "F"); + } + ***/ +} + + +void screenController(void) { + // Show the battery + show_battery(); + display.setColor(WHITE); + + // Show the rates + show_rates(); + + // Toggle Buttons Info + show_toggle_buttons(); + + // Show Gimbals + show_gimbals(); +} + + +void show_gimbals(void) { + display.setColor(WHITE); + + // Draw Box + display.drawRect(18, 0, 45, 45); + display.drawRect(65, 0, 45, 45); + + // Draw dotted lines + for(uint8_t i = 18; i <= 61; i++) { + // display.drawLine(18, 22, 61, 22); + if((i % 5) == 0) { + display.setPixel(i, 22); + display.setPixel(i + 47, 22); + display.setPixel(40, i - 18); + display.setPixel(87, i - 18); + } + } + + // Position of the gimbals + /* + * throttle_val, yaw_val, pitch_val, roll_val + */ + gimbal_left_x = map(yaw_val, 1000, 2000, 19, 62); + gimbal_left_y = map(throttle_val, 1000, 2000, 1, 45); + display.fillCircle(gimbal_left_x, gimbal_left_y, 3); + + gimbal_right_x = map(roll_val, 1000, 2000, 65, 108); + gimbal_right_y = map(pitch_val, 1000, 2000, 1, 45); + display.fillCircle(gimbal_right_x, gimbal_right_y, 3); +} + + +void show_gimbal_left(void) { + display.setColor(WHITE); + + // Draw box + display.drawRect(0, 16, 48, 48); + + // Draw dotted lines + for(uint8_t i = 0; i <= 48; i++) { + if((i % 5) == 0) { + display.setPixel(i, 40); + display.setPixel(24, i + 16); + } + } + + // Draw Gimbal + gimbal_left_x = map(yaw_val, 1000, 2000, 0, 48); + gimbal_left_y = map(throttle_val, 1000, 2000, 16, 64); + display.fillCircle(gimbal_left_x, gimbal_left_y, 3); +} + + +void show_gimbal_right(void) { + display.setColor(WHITE); + + // Draw box + display.drawRect(80, 16, 48, 48); + + // Draw dotted lines + for(uint8_t i = 0; i <= 48; i++) { + if((i % 5) == 0) { + display.setPixel(i + 80, 40); + display.setPixel(104, i + 16); + } + } + + // Draw Gimbal + gimbal_right_x = map(roll_val, 1000, 2000, 80, 128); + gimbal_right_y = map(pitch_val, 1000, 2000, 16, 64); + display.fillCircle(gimbal_right_x, gimbal_right_y, 3); +} + + +void show_battery(void) { + float voltage = voltage_steps * VOLTAGE_MULTIPLER; + float percentage = ((voltage - VOLTAGE_MINIMUM) / VOLTAGE_GAPS) * 100; + + display.setColor(WHITE); + if(percentage > 88) { + display.drawXbm(32, 48, batt_100_width, batt_100_height, batt_100_bits); + } else if(percentage > 76) { + display.drawXbm(32, 48, batt_87_width, batt_87_height, batt_87_bits); + } else if(percentage > 63) { + display.drawXbm(32, 48, batt_75_width, batt_75_height, batt_75_bits); + } else if(percentage > 51) { + display.drawXbm(32, 48, batt_62_width, batt_62_height, batt_62_bits); + } else if(percentage > 38) { + display.drawXbm(32, 48, batt_50_width, batt_50_height, batt_50_bits); + } else if(percentage > 25) { + display.drawXbm(32, 48, batt_37_width, batt_37_height, batt_37_bits); + } else if(percentage > 13) { + display.drawXbm(32, 48, batt_25_width, batt_25_height, batt_25_bits); + } else if(percentage > 5) { + display.drawXbm(32, 48, batt_12_width, batt_12_height, batt_12_bits); + } else { + display.drawXbm(32, 48, batt_00_width, batt_00_height, batt_00_bits); + } +} + + +void show_gimbal_left_toggles(void) { + // Show the control buttons + display.setColor(WHITE); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.drawRect(49, 16, 16, 16); + if(button3) { + display.fillRect(51, 18, 12, 12); + display.setColor(BLACK); + display.drawString(57, 17, "A"); + } else { + display.setColor(WHITE); + display.drawString(57, 17, "A"); + } + + display.setColor(WHITE); + display.drawRect(49, 32, 16, 16); + if(button4) { + display.fillRect(51, 34, 12, 12); + display.setColor(BLACK); + display.drawString(57, 33, "B"); + } else { + display.setColor(WHITE); + display.drawString(57, 33, "B"); + } + + display.setColor(WHITE); + display.drawRect(49, 48, 16, 16); + if(button5) { + display.fillRect(51, 50, 12, 12); + display.setColor(BLACK); + display.drawString(57, 49, "C"); + } else { + display.setColor(WHITE); + display.drawString(57, 49, "C"); + } + + display.setColor(WHITE); + display.drawRect(112, 16, 16, 16); + if(button8) { + display.fillRect(114, 18, 12, 12); + display.setColor(BLACK); + display.drawString(120, 17, "D"); + } else { + display.setColor(WHITE); + display.drawString(120, 17, "D"); + } + + display.setColor(WHITE); + display.drawRect(112, 32, 16, 16); + if(button9) { + display.fillRect(114, 34, 12, 12); + display.setColor(BLACK); + display.drawString(120, 33, "E"); + } else { + display.setColor(WHITE); + display.drawString(120, 33, "E"); + } + + display.setColor(WHITE); + display.drawRect(112, 48, 16, 16); + if(button10) { + display.fillRect(114, 50, 12, 12); + display.setColor(BLACK); + display.drawString(120, 49, "F"); + } else { + display.setColor(WHITE); + display.drawString(120, 49, "F"); + } +} + + +void show_gimbal_right_toggles(void) { + // Show the control buttons + display.setColor(WHITE); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.drawRect(0, 16, 16, 16); + if(button3) { + display.fillRect(2, 18, 12, 12); + display.setColor(BLACK); + display.drawString(8, 17, "A"); + } else { + display.setColor(WHITE); + display.drawString(8, 17, "A"); + } + + display.setColor(WHITE); + display.drawRect(0, 32, 16, 16); + if(button4) { + display.fillRect(2, 34, 12, 12); + display.setColor(BLACK); + display.drawString(8, 33, "B"); + } else { + display.setColor(WHITE); + display.drawString(8, 33, "B"); + } + + display.setColor(WHITE); + display.drawRect(0, 48, 16, 16); + if(button5) { + display.fillRect(2, 50, 12, 12); + display.setColor(BLACK); + display.drawString(8, 49, "C"); + } else { + display.setColor(WHITE); + display.drawString(8, 49, "C"); + } + + display.setColor(WHITE); + display.drawRect(63, 16, 16, 16); + if(button8) { + display.fillRect(65, 18, 12, 12); + display.setColor(BLACK); + display.drawString(71, 17, "D"); + } else { + display.setColor(WHITE); + display.drawString(71, 17, "D"); + } + + display.setColor(WHITE); + display.drawRect(63, 32, 16, 16); + if(button9) { + display.fillRect(65, 34, 12, 12); + display.setColor(BLACK); + display.drawString(71, 33, "E"); + } else { + display.setColor(WHITE); + display.drawString(71, 33, "E"); + } + + display.setColor(WHITE); + display.drawRect(63, 48, 16, 16); + if(button10) { + display.fillRect(65, 50, 12, 12); + display.setColor(BLACK); + display.drawString(71, 49, "F"); + } else { + display.setColor(WHITE); + display.drawString(71, 49, "F"); + } +} + + +void screenGimbalTrimThrottleYaw(void) { + // Button Handlers + if(button8 && (trim_throttle < TRIM_MAX)) { + trim_throttle++; + } else if(button3 && (trim_throttle > -(TRIM_MAX))) { + trim_throttle--; + } + + if(button9 && (trim_yaw < TRIM_MAX)) { + trim_yaw++; + } else if(button4 && (trim_yaw > -(TRIM_MAX))) { + trim_yaw--; + } + + display.setColor(WHITE); + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.drawString(0, 0, "Throttle Yaw Trim"); + + show_gimbal_left(); + show_gimbal_left_toggles(); + + // Show the bars - 45 clicks, 23 = 0, less than 23 are negative and more than 23 are positive + display.drawRect(66, 16, 45, 16); + display.drawRect(66, 32, 45, 16); + // display.drawRect(66, 48, 45, 16); + + // Showing current trim + if(trim_throttle > 0) { + int16_t scale_x = map(trim_throttle, 0, TRIM_MAX, 0, 20); + display.fillRect(89, 18, scale_x, 12); + } else if(trim_throttle < 0) { + int16_t scale_x = map(-(trim_throttle),0, TRIM_MAX, 0, 20); + display.fillRect(89 - scale_x - 1, 18, scale_x, 12); + } else { + display.fillRect(89, 18, 1, 12); + } + + if(trim_yaw > 0) { + int16_t scale_x = map(trim_yaw, 0, TRIM_MAX, 0, 20); + display.fillRect(89, 34, scale_x, 12); + } else if(trim_yaw < 0) { + int16_t scale_x = map(-(trim_yaw),0, TRIM_MAX, 0, 20); + display.fillRect(89 - scale_x - 1, 34, scale_x, 12); + } else { + display.fillRect(89, 34, 1, 12); + } + +} + + +void screenGimbalTrimPitchRoll(void) { + // Button Handlers + if(button8 && (trim_pitch < TRIM_MAX)) { + trim_pitch++; + } else if(button3 && (trim_pitch > -(TRIM_MAX))) { + trim_pitch--; + } + + if(button9 && (trim_roll < TRIM_MAX)) { + trim_roll++; + } else if(button4 && (trim_roll > -(TRIM_MAX))) { + trim_roll--; + } + + display.setColor(WHITE); + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.drawString(0, 0, "Pitch Roll Trim"); + + show_gimbal_right(); + show_gimbal_right_toggles(); + + // Show the bars - 45 clicks, 23 = 0, less than 23 are negative and more than 23 are positive + display.drawRect(17, 16, 45, 16); + display.drawRect(17, 32, 45, 16); + + // Showing current trim + if(trim_pitch > 0) { + int16_t scale_x = map(trim_pitch, 0, TRIM_MAX, 0, 20); + display.fillRect(40, 18, scale_x, 12); + } else if(trim_pitch < 0) { + int16_t scale_x = map(-(trim_pitch),0, TRIM_MAX, 0, 20); + display.fillRect(40 - scale_x - 1, 18, scale_x, 12); + } else { + display.fillRect(40, 18, 1, 12); + } + + if(trim_roll > 0) { + int16_t scale_x = map(trim_roll, 0, TRIM_MAX, 0, 20); + display.fillRect(40, 34, scale_x, 12); + } else if(trim_roll < 0) { + int16_t scale_x = map(-(trim_roll),0, TRIM_MAX, 0, 20); + display.fillRect(40 - scale_x - 1, 34, scale_x, 12); + } else { + display.fillRect(40, 34, 1, 12); + } +} + + +void screenSettings(void) { + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.drawString(0, 0, "Settings"); +} + + +void screenAbout(void) { + display.setTextAlignment(TEXT_ALIGN_LEFT); + display.drawString(0, 0, "About"); +} + + +void show_display(void) { + display.clear(); + + // Based on display mode to show the screen + screens[current_screen](); + + switch(current_screen) { + case SCREEN_INTRO: + if((uint32_t)(millis() - intro_screen_start) > 500) + current_screen = SCREEN_CONTROLLER; + break; + + default: + break; + } + + // Write buffer to display + display.display(); +} + + void display_info(void) { display.clear(); @@ -1001,10 +1551,15 @@ void display_info(void) { display.setFont(ArialMT_Plain_10); display.setColor(WHITE); float voltage = voltage_steps * VOLTAGE_MULTIPLER; - display.drawString(24, 0, String(voltage) + "V"); + display.drawString(22, 0, String(voltage) + "V"); + + display.setTextAlignment(TEXT_ALIGN_RIGHT); + display.drawString(105, 0, String(profile_gimbal_rate) + "G"); - display.drawString(24, 8, String(profile_gimbal_rate) + " G Rate"); - display.drawString(24, 16, String(i2c_counter) + " I2C Rate"); + display.setTextAlignment(TEXT_ALIGN_CENTER); + display.drawString(70, 0, String(i2c_counter) + "R"); + + display.setTextAlignment(TEXT_ALIGN_LEFT); display.drawString(24, 24, "Throttle: " + String(throttle_steps)); display.drawString(24, 32, "Yaw : " + String(yaw_steps)); display.drawString(24, 40, "Roll : " + String(roll_steps)); diff --git a/src/main.h b/src/main.h index ccf1a31..7c9e60d 100644 --- a/src/main.h +++ b/src/main.h @@ -60,7 +60,8 @@ #include "SSD1306Wire.h" // legacy include: `#include "SSD1306.h"` #include "ADS1X15.h" - +#include "bigrc-logo.h" +#include "battery_icons.h" typedef struct struct_data { uint8_t message_type; @@ -86,6 +87,7 @@ typedef struct struct_pairing { uint8_t channel; } struct_pairing; + enum PairingStatus { NOT_PAIRED, PAIR_REQUEST, @@ -179,8 +181,8 @@ uint8_t frame_count_raw = 0; int16_t counter_raw = 0; int16_t counter = 0; uint16_t voltage_steps = 0; -uint16_t current_steps = 0; -uint16_t throttle_steps = 0; +int16_t current_steps = 0; +int16_t throttle_steps = 0; int16_t yaw_steps = 0; int16_t roll_steps = 0; int16_t pitch_steps = 0; @@ -192,6 +194,15 @@ int16_t pitch_val = 0; int16_t pitch_val_tmp = 0; int16_t roll_val = 0; int16_t roll_val_tmp = 0; +int16_t gimbal_left_x = 0; // For Yaw +int16_t gimbal_left_y = 0; // For throttle +int16_t gimbal_right_x = 0; // For Roll +int16_t gimbal_right_y = 0; // For Pitch +int16_t trim_throttle = 0; +int16_t trim_yaw = 0; +int16_t trim_pitch = 0; +int16_t trim_roll = 0; +#define TRIM_MAX 200 // Active calibration int16_t min_throttle = 32767; @@ -211,6 +222,9 @@ uint16_t pool_voltage[MEDIAN_TOTAL]; uint16_t median_voltage(uint16_t val); uint16_t median_get_voltage_steps(void); #define VOLTAGE_MULTIPLER .0049146189 +#define VOLTAGE_MINIMUM 9.00 +#define VOLTAGE_MAXIMUM 12.30 +#define VOLTAGE_GAPS (VOLTAGE_MAXIMUM - VOLTAGE_MINIMUM) uint16_t raw_throttle, raw_yaw, raw_pitch, raw_roll; uint16_t pool_throttle[MEDIAN_TOTAL]; @@ -256,6 +270,44 @@ void printMAC(const uint8_t * mac_addr); void onI2C0Receive(int len); void onI2C0Request(void); void parse_i2c_command(void); -void display_info(void); +void display_info(void); // Deprecated: will be removed once show_display done +void show_display(void); // New method +void show_battery(void); +void show_rates(void); +void show_toggle_buttons(void); +void show_gimbals(void); +void show_gimbal_left(void); +void show_gimbal_left_toggles(void); +void show_gimbal_right(void); +void show_gimbal_right_toggles(void); + +// Screens +typedef void (*Screen)(void); +enum { + SCREEN_INTRO, + SCREEN_CONTROLLER, + SCREEN_GIMBALTRIM_THROTTLEYAW, + SCREEN_GIMBALTRIM_PITCHROLL, + SCREEN_SETTINGS, + SCREEN_ABOUT +}; +void screenIntro(void); +void screenController(void); +void screenGimbalTrimThrottleYaw(void); +void screenGimbalTrimPitchRoll(void); +void screenSettings(void); +void screenAbout(void); +Screen screens[] = { + screenIntro, + screenController, + screenGimbalTrimThrottleYaw, + screenGimbalTrimPitchRoll, + screenSettings, + screenAbout +}; + +int screen_length = (sizeof(screens) / sizeof(Screen)); +uint8_t current_screen = SCREEN_INTRO; +uint32_t intro_screen_start = 0; #endif