├── LICENSE
├── README-en.md
├── README.md
├── balancing_robot
├── balancing_robot.ino
└── sources.h
└── img
├── bbot.jpg
├── parts.jpg
└── schematic.jpeg
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2021 TrashRobotics
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README-en.md:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Self-balancing robot based on NodeMCU
5 |
6 |
7 |
8 |
9 | Русский •
10 | English(Английский)
11 |
12 |
13 | # Description
14 |
15 | Self-balancing robot for fun is capable of:
16 | * actually, to balance; :)
17 | * to ride and turn;
18 | * to deviate from obstacles using distance sensors;
19 | * all of it are controlled through an access point distributed by the robot itself, which acts, among other things, as a web server, issuing a control page to a standard browser upon request.
20 |
21 | # Main parts
22 | * esp8266 NodeMCU v3;
23 | * motor driver l298n;
24 | * yellow single-axis arduino TT-geared motors;
25 | * 2x 18650 batteries and battery compartment;
26 | * MPU6050;
27 | * SSD1306 128x64 I2C display;
28 | * 2x HC-SR04 distance sensors;
29 | * toggle switch KCD1-11;
30 | * breadboard 4x6 см (if you'd like);
31 | * [body parts](https://www.thingiverse.com/thing:4967139)
32 |
33 | 
34 |
35 | # Wiring diagram
36 | 
37 |
38 | # Installation and uploading
39 | To compile the sketch, you need to install the following libraries:
40 | * [ArduinoJson](https://github.com/bblanchon/ArduinoJson);
41 | * [L298N](https://github.com/AndreaLombardo/L298N);
42 | * [MPU6050](https://github.com/ElectronicCats/mpu6050);
43 | * [Ultrasonic](https://github.com/ErickSimoes/Ultrasonic);
44 | * [ThingPulse SSD1306](https://github.com/ThingPulse/esp8266-oled-ssd1306);
45 |
46 | Libraries are installed by following links and clicking **Code->Download ZIP**.
47 | В Arduino IDE **Sketch->Include library->Add .ZIP library...**
48 |
49 | After that you need to download the balancing_robot directory and put it in the Arduino IDE workspace. (sources.h should be in the same folder with the sketch).
50 |
51 | Compile and upload.
52 |
53 | # Start and connection
54 | When the power is turned on, the robot will start balancing.
55 | To control it, you need to connect to an access point :
56 |
57 | ```
58 | ssid: balancingbot; // default
59 | psw: 123456789;
60 | ```
61 | and enter the robot's ip-address in the browser:
62 | ```
63 | 192.168.1.1 // default
64 | ```
65 | have fun :)
66 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Балансирующий робот на NodeMCU
5 |
6 |
7 |
8 |
9 | Русский •
10 | English(Английский)
11 |
12 |
13 | # Описание проекта
14 |
15 | Балансирующий робот, веселья ради, способен:
16 | * собственно, балансировать; :)
17 | * ездить и поворачивать;
18 | * отклоняться от препятствий при помощи датчиков расстояния;
19 | * все это непотребство управляется через точку доступа, раздаваемую
20 | самим роботом, который выступает, в том числе, в качестве web-сервера,
21 | выдавая страницу управления в стандартный браузер, по запросу.
22 |
23 | # Основные детали
24 | * esp8266 NodeMCU v3;
25 | * драйвер двигателей l298n;
26 | * желтые одноосевые ардуино TT-мотор-редукторы;
27 | * 2x 18650 Аккумуляторы и батарейный отсек для них
28 | * MPU6050;
29 | * SSD1306 128x64 I2C дисплей;
30 | * 2x HC-SR04 датчики расстояния;
31 | * тумблер KCD1-11;
32 | * макетная плата 4x6 см (по желанию);
33 | * [детали корпуса](https://www.thingiverse.com/thing:4967139)
34 |
35 | 
36 |
37 | # Схема подключения
38 | 
39 |
40 | # Установка и прошивка
41 | Для компиляции скетча нужно установить следующие библиотеки:
42 | * [ArduinoJson](https://github.com/bblanchon/ArduinoJson);
43 | * [L298N](https://github.com/AndreaLombardo/L298N);
44 | * [MPU6050](https://github.com/ElectronicCats/mpu6050);
45 | * [Ultrasonic](https://github.com/ErickSimoes/Ultrasonic);
46 | * [ThingPulse SSD1306](https://github.com/ThingPulse/esp8266-oled-ssd1306);
47 |
48 | Библиотеки устанавливаются переходом по ссылкам и нажатием **Code->Download ZIP**.
49 | В Arduino IDE **Скетч->Подключить библиотеку->Добавить .ZIP библиотеку...**
50 |
51 | После этого скачиваем директорию balancing_robot и кладем ее в рабочее пространство Arduino IDE.
52 | (sources.h должен лежать в одной папке со скетчем).
53 |
54 | Компилируем и прошиваем.
55 |
56 | # Включение и подключение
57 | При включении питания робот начнет балансировать.
58 | Для управления необходимо подключиться к точке доступа:
59 | ```
60 | ssid: balancingbot; // по умолчанию
61 | psw: 123456789;
62 | ```
63 | и ввести в браузере ip-адрес робота:
64 | ```
65 | 192.168.1.1 // по умолчанию
66 | ```
67 | развлекайтесь
68 |
--------------------------------------------------------------------------------
/balancing_robot/balancing_robot.ino:
--------------------------------------------------------------------------------
1 | /*
2 | Скетч к проекту балансирующего робота
3 | Github: https://github.com/TrashRobotics/BalancingRobot
4 | Страница канала на YouTube: https://www.youtube.com/channel/UCHRTaqr8KSCfyo2_CLH-yfg
5 | Автор: TrashRobotics
6 | */
7 | #include
8 | #include
9 | #include "ArduinoJson.h"
10 | #include
11 | #include "SSD1306Wire.h"
12 | #include "MPU6050.h"
13 | #include "Wire.h"
14 | #include "String.h"
15 | #include
16 | #include
17 | #include "sources.h" // изображения, web-страницы, css и т.д.
18 |
19 |
20 | #define MPU_ADRESS 0x68 // адреса I2C устройств
21 | #define SCREEN_ADDRESS 0x3C //
22 |
23 | #define EEPROM_RW_ADDR 0x00 // адресс чтения-записи в eeprom
24 | #define EEPROM_INIT_KEY 0x04 // ключ проверки - проводилась ли первоначальная инициализация eeprom
25 |
26 | #define VOLTAGE_REF 3.3f // питающее esp напряжение
27 | #define VOLTAGE_GAIN 3.94f // коэффициент передачи делителя напряжения 13V <-> 3.3V
28 | #define VOLTAGE_OFFSET 60 // 60 // ошибка измерения аналогового выхода
29 | #define MIN_SUPPLY_VOLTAGE 6.5f // минимальное напряжение АКБ
30 | #define LOW_VOLTAGE_WARNING_MSG_PERIOD 15000 // в миллисекундах
31 |
32 | #define SDA_PIN D1 // пины шины I2C
33 | #define SCL_PIN D2 //
34 | #define VOLTAGE_PIN A0 // пин для считывания напряжения с li-ion
35 | #define US_TRIG_PIN D3 // общий пин для входа trig c ультразвуковых датчиков
36 | #define US_ECHO1_PIN D5 // пины для выходов echo с ультразвуковых датчиков
37 | #define US_ECHO2_PIN D6 //
38 | #define ENA_PIN D7 // пины драйвера моторов l298n
39 | #define ENB_PIN D8 //
40 | #define IN1_PIN D0 //
41 | #define IN2_PIN D4 //
42 | #define IN3_PIN D9 //
43 | #define IN4_PIN D10 //
44 |
45 | #define MAX_P_VALUE 30 // максимальное значение пропорционального коэффициента (в основном нужно для слайдера в web странице)
46 | #define MAX_I_VALUE 300 // максимальное значение интегрального коэффициента (в основном нужно для слайдера в web странице)
47 | #define MAX_D_VALUE 5 // максимальное значение дифференциального коэффициента (в основном нужно для слайдера в web странице)
48 |
49 | // экземпляры используемых классов
50 | ESP8266WebServer webServer(80);
51 | IPAddress ip(192,168,1,1);
52 | IPAddress gateway(192,168,1,1);
53 | IPAddress subnet(255,255,255,0);
54 | StaticJsonDocument<400> jsondoc;
55 |
56 | MPU6050 mpu(MPU_ADRESS);
57 | SSD1306Wire display(SCREEN_ADDRESS, SDA_PIN, SCL_PIN);
58 | L298NX2 motors(ENA_PIN, IN1_PIN, IN2_PIN, ENB_PIN, IN3_PIN, IN4_PIN);
59 | Ultrasonic ultrasonicFront(US_TRIG_PIN, US_ECHO1_PIN);
60 | Ultrasonic ultrasonicBack(US_TRIG_PIN, US_ECHO2_PIN);
61 |
62 | // данные точки доступа
63 | const char *ssid = "balancingbot";
64 | const char *password = "123456789";
65 |
66 | // настраиваемые коэффициенты (можно впоследствие вынести в web страницу)
67 | float alfaAg = 0.02; // коэффициент ФНЧ угла отклонения
68 | float kP = 12.0; // пропорциональный коэффициент PID-регулятора
69 | float kI = 0.0; // интегральный коэффициент PID-регулятора
70 | float kD = 0.01; // дифференциальный коэффициент PID-регулятора
71 | float target = -2.0; // базовый угол удержания платформы в градусах
72 | float targetDeadZone = 1.0; // мертвая зона около угла удержания
73 | float moveAdditionalAngle = 3.0; // добавочный угол, за счет которого производится передвижение
74 |
75 | bool isAfraid = true; // флаг, используются ли датчики расстояния, для определения препятствий
76 | uint16_t minAfraidDistance = 10; // минимальное расстояние, после которого платформа отъезжает от препятствия (в сантиметрах)
77 |
78 | int16_t accXoffset = -80; // компенсация смещений IMU датчика
79 | int16_t accYoffset = -80; //
80 | int16_t accZoffset = -620; //
81 |
82 | int16_t gyroXoffset = 15; //
83 | int16_t gyroYoffset = -350; //
84 | int16_t gyroZoffset = 40; //
85 |
86 | uint8_t minAbsSpeed = 100; // минимальая скорость, подаваемая на моторы: вместо [0-255] <-> [minAbsSpeed-255]
87 | float stopAngle = 30; // наибольший угол отклонения в обе стороны, после которого робот останавливается
88 | uint8_t movePeriod = 10; // период обовления управляющих сигналов в миллисекундах // если делать меньше точка доступа глохнет
89 |
90 | float speedFactorA = 0.91; // дополнительные параметры компенсирующие разницу характеристик моторов
91 | float speedFactorB = 0.99; //
92 | float rotateAdditionalSpeed = 50; // добавочная скорость, суммирующаяся с основной, за счет которой производится поворот на месте
93 |
94 | // сохраняемые в eeprom данные
95 | struct StoredData{
96 | uint8_t key; // проверка на первую инициализацию: если key != EEPROM_INIT_KEY, то данные еще не были записаны
97 | float kP;
98 | float kI;
99 | float kD;
100 | };
101 |
102 | // состояния конечного автомата
103 | enum FsmStates
104 | {
105 | INITIALIZATION, // инициализация системы
106 | LOW_VOLTAGE, // прерывает инициализацию и работу, уходит в полуспящий режим
107 | BALANCING, // обычный режим работы
108 | ERROR // если появилась какая-то ошибка
109 | };
110 |
111 | // глобальные переменные
112 | FsmStates state = FsmStates::INITIALIZATION;
113 | uint32_t lowVoltageTimer = 0; // таймер показа сообщения о низком заряде
114 | uint32_t pidTimer = 0; // таймер обновления управляющих сигналов
115 | bool afraidFlag = false; // флаг - было ли замечено препятствие
116 | int16_t ax, ay, az; // вынесены как глобальные, чтоб можно было позже сделать калибровку через web страницу
117 | int16_t wx, wy, wz; //
118 | float additionalAngle = 0.f; // действующая добавка к углу удержания
119 | float additionalSpeed = 0.f; // действующая добавка к скорости
120 | float angle = 0.f; // текущий угол наклона, снятый с MPU
121 |
122 |
123 | // предъобявление некоторых функций с параметрами по умолчанию из-за костылей arduino IDE
124 | void smoothProgressBar(uint8_t progressStart, uint8_t progressEnd, String text, uint8_t dt=30);
125 | float pid(float input, float trgt, float kp, float ki, float kd, float dt, bool reset=false);
126 |
127 |
128 | void setup() {
129 | // настройка переферии
130 | pinMode(ENA_PIN, OUTPUT);
131 | pinMode(ENB_PIN, OUTPUT);
132 | pinMode(IN1_PIN, OUTPUT);
133 | pinMode(IN2_PIN, OUTPUT);
134 | pinMode(IN3_PIN, OUTPUT);
135 | pinMode(IN4_PIN, OUTPUT);
136 |
137 | Wire.begin(SDA_PIN, SCL_PIN);
138 | }
139 |
140 |
141 | void loop() {
142 | switch(state){
143 | case FsmStates::INITIALIZATION:{
144 | // инициализация дисплея
145 | display.init();
146 | display.flipScreenVertically();
147 | display.setFont(ArialMT_Plain_10);
148 | display.clear();
149 | display.drawXbm(32, 0, LOGO_WIDTH, LOGO_HEIGHT, logoBits); // рисуем лого
150 | display.display();
151 | delay(3000);
152 |
153 | // рисуем полосу загрузки, которые также используются как delay
154 | smoothProgressBar(0, 10, "Check voltage...");
155 | smoothProgressBar(11, 20, "Voltage: " + String(getVoltage()) + " V");
156 |
157 | if(getVoltage() < MIN_SUPPLY_VOLTAGE){
158 | state = FsmStates::LOW_VOLTAGE;
159 | progressBar(21, "Voltage is low");
160 | delay(500);
161 | break; // останавливаем инициализацию
162 | }
163 |
164 | smoothProgressBar(22, 30, "Voltage is acceptable");
165 | smoothProgressBar(31, 40, "MPU initialize...");
166 |
167 | mpu.initialize(); // инициализация IMU
168 | if(!mpu.testConnection()){
169 | state = FsmStates::ERROR;
170 | progressBar(41, "MPU connection failed");
171 | delay(500);
172 | break;
173 | }
174 | mpu.setFullScaleAccelRange(MPU6050_ACCEL_FS_4); // настройка IMU
175 | mpu.setFullScaleGyroRange(MPU6050_GYRO_FS_500); //
176 |
177 | smoothProgressBar(42, 50, "MPU initializing successful");
178 | smoothProgressBar(51, 60, "EEPROM initialize...");
179 |
180 | EEPROM.begin(512);
181 | StoredData stval; // создаем структуру, читаемую из eeprom
182 | EEPROM.get(EEPROM_RW_ADDR, stval);
183 |
184 | smoothProgressBar(61, 65, "EEPROM check first initialization...");
185 |
186 | if(stval.key != EEPROM_INIT_KEY){ // если запись в eeprom никогда не производилась
187 | stval.key = EEPROM_INIT_KEY;
188 | stval.kP = kP;
189 | stval.kI = kI;
190 | stval.kD = kD;
191 | EEPROM.put(EEPROM_RW_ADDR, stval); // записываем значения по умолчанию
192 | EEPROM.commit();
193 | smoothProgressBar(66, 72, "EEPROM first initialize...");
194 | }
195 | else{ // если запись уже производилась, то загружаем данные из eeprom
196 | kP = stval.kP;
197 | kI = stval.kI;
198 | kD = stval.kD;
199 | smoothProgressBar(66, 72, "EEPROM reading data...");
200 | }
201 |
202 | smoothProgressBar(73, 80, "WIFI AP initialize...");
203 | //настраиваем точку доступа
204 | WiFi.mode(WIFI_AP);
205 | WiFi.softAPConfig(ip, gateway, subnet);
206 | bool result = WiFi.softAP(ssid, password);
207 | if (!result){
208 | state = FsmStates::ERROR;
209 | progressBar(81, "WiFi softAP failed");
210 | delay(500);
211 | break;
212 | }
213 |
214 | smoothProgressBar(82, 90, "Web server initialize...");
215 | // подключаем обработчики GET запросов
216 | webServer.on("/", handleControl); // корневая директория - страница управления
217 | webServer.on("/settings", handleSettings); // страница настроек pid-регулятора
218 | webServer.on("/about", handleAbout); // страница about
219 | webServer.on("/general.css", handleCss); // отдельно сервится таблица стилей
220 | webServer.on("/getData", handleGetData); // обработчик запроса на получение данных html страницей
221 | webServer.on("/setPid", handleSetPid); // обработчик запроса на установку значения PID коэффициентов
222 | webServer.on("/saveData", handleSaveData); // обработчик запроса на сохраение текущих PID коэффициентов в eeprom
223 | webServer.on("/move", handleMove); // обработчик запросов передвижения платформы
224 | webServer.onNotFound(handleNotFound);
225 | webServer.begin();
226 |
227 | smoothProgressBar(91, 99, "Web server initialize...");
228 |
229 | state = FsmStates::BALANCING; // переключаемся в рабочее состояние
230 | progressBar(100, "Loading is complete");
231 | delay(500);
232 | break;
233 | }
234 |
235 | case FsmStates::LOW_VOLTAGE:{ // переодически зажигает экран на 3 секунды, говоря, что АКБ сел
236 | if ((millis() > lowVoltageTimer + LOW_VOLTAGE_WARNING_MSG_PERIOD) || (lowVoltageTimer == 0)){
237 | displayLowVoltage();
238 | delay(3000);
239 | display.clear();
240 | display.display();
241 | lowVoltageTimer = millis();
242 | }
243 | break;
244 | }
245 |
246 | case FsmStates::BALANCING:{
247 | if (!checkVoltage()){ // проверяется раз в секунду, т.к., если часто дергать аналоговый выход, падает вайвай -__-
248 | moveA(0); // останавливаем моторы
249 | moveB(0);
250 | state = FsmStates::LOW_VOLTAGE;
251 | delay(100);
252 | break;
253 | }
254 |
255 | if (millis() > pidTimer + movePeriod){
256 | angle = getAngleY() * RAD_TO_DEG; // получаем угол по оси Y
257 | float dt = ((float)(millis() - pidTimer)/1000.f);
258 | float speed = 0.f;
259 | if (abs(angle) < stopAngle){ // если робот НЕ наклонился слишком сильно
260 | speed = pid(angle, target + additionalAngle, kP, kI, kD, dt); // получаем скорость с PID-регулятора
261 | speed = (speed/abs(speed))*(abs(speed) + minAbsSpeed); // добавлем к ее модулю минимальное значение
262 | speed = -speed; // инвертируем скорость
263 | }
264 | else{
265 | pid(0.f, 0.f, 0.f, 0.f, 0.f, 0.f, true); // сбрасываем данные pid регулятора (reset=true)
266 | speed = 0.f; // скорость на ноль
267 | }
268 |
269 | if (isAfraid){
270 | if (checkWallOnFront() && checkWallOnBack()){ // если препятствие и спереди и сзади, то балансируем на месте
271 | additionalAngle = 0.f;
272 | additionalSpeed = 0.f;
273 | afraidFlag = true;
274 | } else if (checkWallOnFront()) {
275 | additionalAngle = -moveAdditionalAngle; // двигаемся назад
276 | additionalSpeed = 0.f; // и не поворачивваем
277 | afraidFlag = true;
278 | } else if (checkWallOnBack()) {
279 | additionalAngle = moveAdditionalAngle; // двигаемся вперед
280 | additionalSpeed = 0.f; // и не поворачивваем
281 | afraidFlag = true;
282 | } else if (afraidFlag) { // если до этого уезжали от препятствия
283 | additionalAngle = 0.f;
284 | additionalSpeed = 0.f;
285 | afraidFlag = false;
286 | }
287 | }
288 |
289 | // добавление мертвой зоны
290 | if ((angle <= (target + targetDeadZone/2.f)) && (angle >= (target - targetDeadZone/2.f)) && (additionalAngle == 0.f)) {
291 | speed = 0.f;
292 | }
293 |
294 | moveA(constrain(speed*speedFactorA - additionalSpeed, -255.f, 255.f)); // двигаем моторы, учитывая их разницу в характеристиках +
295 | moveB(constrain(speed*speedFactorB + additionalSpeed, -255.f, 255.f)); // добавляем скорости на моторы для поворота, если он есть
296 |
297 | displayFace();
298 | //displayMpuRaw(); // функции для дебага
299 | //displayAngleAndSpeed(speed, angle); //
300 | //displayDistance(ultrasonicFront.read(), ultrasonicBack.read()); //
301 |
302 | pidTimer = millis();
303 | }
304 | break;
305 | }
306 |
307 | case FsmStates::ERROR:{
308 | break;
309 | }
310 |
311 | default: {
312 | break;
313 | }
314 | }
315 | webServer.handleClient();
316 | }
317 |
318 |
319 | void handleControl() {
320 | webServer.send_P(200, "text/html", controlHtml); // отправляем веб страницу
321 | }
322 |
323 |
324 | void handleSettings() {
325 | webServer.send_P(200, "text/html", settingsHtml); // отправляем веб страницу
326 | }
327 |
328 |
329 | void handleAbout() {
330 | webServer.send_P(200, "text/html", aboutHtml); // отправляем веб страницу
331 | }
332 |
333 |
334 | void handleCss() {
335 | webServer.send_P(200, "text/css", generalCss); // отправляем талицу стилей
336 | }
337 |
338 |
339 | void handleNotFound(){
340 | webServer.send(404, "text/plain", "404: Not found");
341 | }
342 |
343 |
344 | void handleMove(){
345 | String direction = webServer.arg("direction"); // получаем значение направления перемещения (была нажата или отдата кнопка движения)
346 | String value = webServer.arg("value"); // значение была ли нажата (value == 1) или отжата (value == 0) кнопка
347 | if (value.toInt() == 1){
348 | if (direction.equals("forward")) additionalAngle = moveAdditionalAngle;
349 | else if (direction.equals("backward")) additionalAngle = -moveAdditionalAngle;
350 | else if (direction.equals("left")) {
351 | additionalSpeed = rotateAdditionalSpeed;
352 | additionalAngle = moveAdditionalAngle; // немного наклоняемся вперед
353 | }
354 | else if (direction.equals("right")) {
355 | additionalSpeed = -rotateAdditionalSpeed;
356 | additionalAngle = moveAdditionalAngle; // немного наклоняемся вперед
357 | }
358 | }
359 | else{
360 | additionalAngle = 0.f;
361 | additionalSpeed = 0.f;
362 | }
363 | webServer.send(200, "text/plane", "");
364 | }
365 |
366 |
367 | void handleGetData() {
368 | jsondoc["maxPvalue"] = MAX_P_VALUE; // отправляем на страницу максимальные значения слайдеров настройки
369 | jsondoc["maxIvalue"] = MAX_I_VALUE; // PID коэффициентов
370 | jsondoc["maxDvalue"] = MAX_D_VALUE; //
371 | jsondoc["kP"] = kP; // и текущие значения PID коэффициентов
372 | jsondoc["kI"] = kI; //
373 | jsondoc["kD"] = kD; //
374 | String output;
375 | serializeJson(jsondoc, output); // создаем json-строку
376 | webServer.send(200, "application/json", output); // отправляем ее на страницу
377 | }
378 |
379 |
380 | void handleSetPid()
381 | {
382 | kP = webServer.arg("kP").toFloat(); // получаем значения, введенные пользователем, из на
383 | kI = webServer.arg("kI").toFloat(); //
384 | kD = webServer.arg("kD").toFloat(); //
385 | webServer.send(200, "text/plane", "");
386 | }
387 |
388 |
389 | void handleSaveData()
390 | {
391 | StoredData stval; // создаем структуру, записываемую в eeprom
392 | stval.key = EEPROM_INIT_KEY;
393 | stval.kP = kP;
394 | stval.kI = kI;
395 | stval.kD = kD;
396 | EEPROM.put(EEPROM_RW_ADDR, stval); // записываем
397 | EEPROM.commit();
398 | webServer.send(200, "text/plane", "");
399 | }
400 |
401 |
402 | void moveA(int16_t speed){
403 | motors.setSpeedA(abs(speed));
404 | if (speed >= 0) motors.forwardA();
405 | else if (speed < 0) motors.backwardA();
406 | }
407 |
408 |
409 | void moveB(int16_t speed){
410 | motors.setSpeedB(abs(speed));
411 | if (speed >= 0) motors.forwardB();
412 | else if (speed < 0) motors.backwardB();
413 | }
414 |
415 |
416 | float pid(float input, float trgt, float kp, float ki, float kd, float dt, bool reset){
417 | static float integral = 0.f;
418 | static float lastError = 0.f;
419 |
420 | if(reset){
421 | integral = 0.f;
422 | lastError = 0.f;
423 | return 0.f;
424 | }
425 | float error = trgt - input;
426 | integral += error * dt * ki;
427 | float diff = (error - lastError) / dt;
428 |
429 | lastError = error;
430 | return error * kp + integral + diff * kd;
431 | }
432 |
433 |
434 | float getVoltage(){
435 | return (float)(constrain((int16_t)analogRead(VOLTAGE_PIN) - VOLTAGE_OFFSET, 0, 1024)) * VOLTAGE_REF * VOLTAGE_GAIN / 1024.f;
436 | }
437 |
438 |
439 | bool checkVoltage()
440 | {
441 | static uint32_t checkTimer = millis();
442 | static bool result = true;
443 | if (millis() > checkTimer + 1500) { // проверяет напряжение раз в секунду
444 | result = getVoltage() > MIN_SUPPLY_VOLTAGE;
445 | checkTimer = millis();
446 | }
447 | return result;
448 | }
449 |
450 |
451 | void getAccGyro(float* accgyro){
452 | mpu.getMotion6(&ax, &ay, &az, &wx, &wy, &wz); // получаем данные с MPU
453 | ax += accXoffset;
454 | ay += accYoffset;
455 | az += accZoffset;
456 | wx += gyroXoffset;
457 | wy += gyroYoffset;
458 | wz += gyroZoffset;
459 |
460 | // преобразуем их
461 | accgyro[0] = ((float)ax) / 32768.f * 4.f; // ускорения
462 | accgyro[1] = ((float)ay) / 32768.f * 4.f;
463 | accgyro[2] = ((float)az) / 32768.f * 4.f;
464 |
465 | accgyro[3] = ((float)wx) / 32768.f * 500.f; // угловые скорости
466 | accgyro[4] = ((float)wy) / 32768.f * 500.f;
467 | accgyro[5] = ((float)wz) / 32768.f * 500.f;
468 | }
469 |
470 |
471 | float getAngleY(){ // угол вокруг оси Y
472 | static uint32_t angleTimer = millis(); // локальный таймер
473 | static float angleY = 0.0; // локально храним значения угла
474 |
475 | float accgyro[6];
476 | float dt;
477 |
478 | getAccGyro(accgyro); // получаем преобразованные данные с IMU
479 |
480 | dt = ((float)(millis() - angleTimer) / 1000.f); // промежуток времени между измерениями в секундах
481 |
482 | float accAngleY = atan2(accgyro[0], accgyro[2]); // угол через ускорения = арктангенсу проекций на оси X и Z
483 | float gyroAngleY = angleY + DEG_TO_RAD*(-accgyro[4])*dt; // угол через угловую скорость - интеграл скорости по оси Y
484 |
485 | angleY = alfaAg*accAngleY + (1-alfaAg)*gyroAngleY; // альфа-бета фильтрация
486 | angleTimer = millis();
487 |
488 | return angleY;
489 | }
490 |
491 |
492 | bool checkWallOnFront(){
493 | static bool isFrontWall = false;
494 | static uint32_t checkTimer = millis();
495 | if (millis() > checkTimer + 50) { // проверяет расстояние раз в полсекунды
496 | isFrontWall = ultrasonicFront.read() <= minAfraidDistance;
497 | checkTimer = millis();
498 | }
499 | return isFrontWall;
500 | }
501 |
502 |
503 | bool checkWallOnBack(){
504 | static bool isBackWall = false;
505 | static uint32_t checkTimer = millis();
506 | if (millis() > checkTimer + 50) { // проверяет расстояние раз в полсекунды
507 | isBackWall = ultrasonicBack.read() <= minAfraidDistance;
508 | checkTimer = millis();
509 | }
510 | return isBackWall;
511 | }
512 |
513 |
514 | void progressBar(uint8_t progress, String text){
515 | display.clear();
516 | display.setFont(ArialMT_Plain_16);
517 | display.setTextAlignment(TEXT_ALIGN_CENTER);
518 | display.drawString(64, 10, "Loading: " + String(progress) + "%");
519 | display.drawProgressBar(3, 30, 125, 10, progress);
520 | display.setTextAlignment(TEXT_ALIGN_LEFT);
521 | display.setFont(ArialMT_Plain_10);
522 | display.drawString(5, 50, text);
523 | display.display();
524 | }
525 |
526 |
527 | void smoothProgressBar(uint8_t progressStart, uint8_t progressEnd, String text, uint8_t dt){
528 | for(uint8_t i = progressStart; i <= progressEnd; i++){ // плавная прорисовка
529 | progressBar(i, text);
530 | delay(dt);
531 | }
532 | }
533 |
534 |
535 | void displayLowVoltage(){
536 | display.clear();
537 | display.drawXbm(36, 20, BATTERY_WIDTH, BATTERY_HEIGHT, batteryBits); // рисуем
538 | display.setFont(ArialMT_Plain_10);
539 | display.setTextAlignment(TEXT_ALIGN_CENTER);
540 | display.drawString(64, 0, "LOW VOLTAGE: " + String(getVoltage())+ " V");
541 | display.setFont(ArialMT_Plain_10);
542 | display.drawString(64, 50, "power on and reboot");
543 | display.display();
544 | }
545 |
546 |
547 | void displayFace(){
548 | static enum {
549 | HAPPY,
550 | NORMAL,
551 | CONFUSED,
552 | DISAPPOINTED
553 | } faceState = HAPPY;
554 | static uint32_t displayFaceTimer = millis(); // локальный таймер
555 | static uint32_t faceUpdatePerion = 700; // период обновления морды робота в мс
556 | static uint8_t count = 0;
557 |
558 | if (millis() > displayFaceTimer + faceUpdatePerion){
559 | switch(faceState){
560 | case HAPPY:{
561 | if (abs(angle) > stopAngle) faceState = CONFUSED;
562 | else if (abs(angle) > stopAngle/5) faceState = NORMAL;
563 |
564 | display.clear();
565 | display.drawXbm(24, 2, FACE_WIDTH, FACE_HEIGHT, faceHappyBits);
566 | display.display();
567 | break;
568 | }
569 | case NORMAL:{
570 | if (abs(angle) > stopAngle) faceState = CONFUSED;
571 | else if (abs(angle) <= stopAngle/5) faceState = HAPPY;
572 | display.clear();
573 | display.drawXbm(24, 2, FACE_WIDTH, FACE_HEIGHT, faceNormalBits);
574 | display.display();
575 | break;
576 | }
577 | case CONFUSED:{
578 | if (abs(angle) <= stopAngle/5) faceState = DISAPPOINTED;
579 | display.clear();
580 | display.drawXbm(24, 2, FACE_WIDTH, FACE_HEIGHT, faceConfusedBits);
581 | display.display();
582 | break;
583 | }
584 | case DISAPPOINTED:{
585 | if (count > 6) {
586 | faceState = HAPPY;
587 | count = 0;
588 | break;
589 | } else if (count > 3){
590 | display.clear();
591 | display.setFont(ArialMT_Plain_10);
592 | display.drawString(0, 0, "Hey meatbag! Couldn't \n you create me so \n that I don't fall?");
593 | display.display();
594 | } else {
595 | display.clear();
596 | display.drawXbm(24, 2, FACE_WIDTH, FACE_HEIGHT, faceDisappointedBits);
597 | display.display();
598 | }
599 | count++;
600 | break;
601 | }
602 | default: {
603 | break;
604 | }
605 | }
606 | displayFaceTimer = millis();
607 | }
608 | }
609 |
610 |
611 | /*
612 | void displayMpuRaw(){ // debug function
613 | display.clear();
614 | display.setFont(ArialMT_Plain_10);
615 | display.setTextAlignment(TEXT_ALIGN_LEFT);
616 | display.drawString(0, 0, "ax: " + String(ax));
617 | display.drawString(0, 20, "ay: " + String(ay));
618 | display.drawString(0, 40, "az: " + String(az));
619 | display.drawString(64, 0, "wx: " + String(wx));
620 | display.drawString(64, 20, "wy: " + String(wy));
621 | display.drawString(64, 40, "wz: " + String(wz));
622 | display.display();
623 | }
624 |
625 |
626 | void displayAngleAndSpeed(float speed, float angle){ // debug function
627 | display.clear();
628 | display.setFont(ArialMT_Plain_16);
629 | display.setTextAlignment(TEXT_ALIGN_LEFT);
630 | display.drawString(0, 10, "angle: " + String((int)angle));
631 | display.drawString(0, 30, "speed: " + String((int)speed));
632 | display.display();
633 | }
634 |
635 |
636 | void displayDistance(float front, float back){
637 | display.clear();
638 | display.setFont(ArialMT_Plain_16);
639 | display.setTextAlignment(TEXT_ALIGN_LEFT);
640 | display.drawString(0, 10, "distanceFront: " + String((int)front));
641 | display.drawString(0, 30, "distanceBack: " + String((int)back));
642 | display.display();
643 | }
644 | */
645 |
--------------------------------------------------------------------------------
/balancing_robot/sources.h:
--------------------------------------------------------------------------------
1 | #define LOGO_WIDTH 64
2 | #define LOGO_HEIGHT 64
3 |
4 | #define BATTERY_WIDTH 56
5 | #define BATTERY_HEIGHT 27
6 |
7 | #define FACE_WIDTH 80
8 | #define FACE_HEIGHT 60
9 |
10 | const uint8_t logoBits[] PROGMEM = {
11 | 0x00, 0x00, 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0xff,
12 | 0xff, 0x07, 0x00, 0x00, 0x00, 0x00, 0xfc, 0x01, 0x80, 0x3f, 0x00, 0x00,
13 | 0x00, 0x00, 0x3f, 0x00, 0x00, 0xfc, 0x00, 0x00, 0x00, 0x80, 0x07, 0x00,
14 | 0x00, 0xe0, 0x01, 0x00, 0x00, 0xe0, 0x01, 0x00, 0x00, 0x80, 0x07, 0x00,
15 | 0x00, 0xf0, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x38, 0x00, 0x00,
16 | 0x00, 0x00, 0x1c, 0x00, 0x00, 0x1c, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00,
17 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0x00, 0x07, 0x00, 0x00,
18 | 0x00, 0x00, 0xe0, 0x00, 0x80, 0x03, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x01,
19 | 0xc0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x80, 0x03, 0xe0, 0x00, 0x00, 0x00,
20 | 0x00, 0x00, 0x00, 0x07, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06,
21 | 0x70, 0xf0, 0xff, 0xff, 0xff, 0x00, 0x00, 0x0e, 0x38, 0xf0, 0xff, 0xff,
22 | 0xff, 0x00, 0x00, 0x1c, 0x18, 0xf0, 0xff, 0xff, 0xff, 0x00, 0x00, 0x18,
23 | 0x1c, 0xf0, 0xff, 0xff, 0xff, 0x00, 0x00, 0x38, 0x0c, 0xf0, 0xff, 0xff,
24 | 0xff, 0x00, 0x00, 0x30, 0x0c, 0xf0, 0xff, 0xff, 0xff, 0x00, 0x00, 0x30,
25 | 0x0e, 0x00, 0x80, 0x1f, 0x00, 0x00, 0x00, 0x70, 0x06, 0x00, 0x80, 0x1f,
26 | 0x00, 0x00, 0x00, 0x60, 0x06, 0x00, 0x80, 0x9f, 0xff, 0x3f, 0x00, 0x60,
27 | 0x07, 0x00, 0x80, 0x9f, 0xff, 0xff, 0x00, 0xe0, 0x03, 0x00, 0x80, 0x9f,
28 | 0xff, 0xff, 0x03, 0xc0, 0x03, 0x00, 0x80, 0x9f, 0xff, 0xff, 0x07, 0xc0,
29 | 0x03, 0x00, 0x80, 0x9f, 0xff, 0xff, 0x0f, 0xc0, 0x03, 0x00, 0x80, 0x9f,
30 | 0x0f, 0xf0, 0x0f, 0xc0, 0x03, 0x00, 0x80, 0x9f, 0x0f, 0xe0, 0x1f, 0xc0,
31 | 0x03, 0x00, 0x80, 0x9f, 0x0f, 0xc0, 0x1f, 0xc0, 0x03, 0x00, 0x80, 0x9f,
32 | 0x0f, 0x80, 0x1f, 0xc0, 0x03, 0x00, 0x80, 0x9f, 0x0f, 0x80, 0x1f, 0xc0,
33 | 0x03, 0x00, 0x80, 0x9f, 0x0f, 0x80, 0x1f, 0xc0, 0x03, 0x00, 0x80, 0x9f,
34 | 0x0f, 0xc0, 0x0f, 0xc0, 0x03, 0x00, 0x80, 0x9f, 0x0f, 0xc0, 0x0f, 0xc0,
35 | 0x03, 0x00, 0x80, 0x9f, 0x0f, 0xe0, 0x07, 0xc0, 0x03, 0x00, 0x80, 0x9f,
36 | 0xff, 0xff, 0x07, 0xc0, 0x03, 0x00, 0x80, 0x9f, 0xff, 0xff, 0x03, 0xc0,
37 | 0x07, 0x00, 0x80, 0x9f, 0xff, 0xff, 0x01, 0xe0, 0x06, 0x00, 0x80, 0x9f,
38 | 0xff, 0x7f, 0x00, 0x60, 0x06, 0x00, 0x80, 0x9f, 0xff, 0x3f, 0x00, 0x60,
39 | 0x0e, 0x00, 0x80, 0x9f, 0x0f, 0x7e, 0x00, 0x70, 0x0c, 0x00, 0x80, 0x9f,
40 | 0x0f, 0xfc, 0x00, 0x30, 0x0c, 0x00, 0x80, 0x9f, 0x0f, 0xfc, 0x01, 0x30,
41 | 0x1c, 0x00, 0x80, 0x9f, 0x0f, 0xf8, 0x01, 0x38, 0x18, 0x00, 0x80, 0x9f,
42 | 0x0f, 0xf0, 0x03, 0x18, 0x38, 0x00, 0x80, 0x9f, 0x0f, 0xf0, 0x03, 0x1c,
43 | 0x70, 0x00, 0x80, 0x9f, 0x0f, 0xe0, 0x07, 0x0e, 0x60, 0x00, 0x80, 0x9f,
44 | 0x0f, 0xe0, 0x07, 0x06, 0xe0, 0x00, 0x80, 0x9f, 0x0f, 0xc0, 0x0f, 0x07,
45 | 0xc0, 0x01, 0x80, 0x9f, 0x0f, 0xc0, 0x8f, 0x03, 0x80, 0x03, 0x80, 0x9f,
46 | 0x0f, 0x80, 0xc7, 0x01, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
47 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0x00, 0x1c, 0x00, 0x00,
48 | 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x00, 0x1c, 0x00,
49 | 0x00, 0xf0, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0xe0, 0x01, 0x00,
50 | 0x00, 0x80, 0x07, 0x00, 0x00, 0x80, 0x07, 0x00, 0x00, 0xe0, 0x01, 0x00,
51 | 0x00, 0x00, 0x3f, 0x00, 0x00, 0xfc, 0x00, 0x00, 0x00, 0x00, 0xfc, 0x00,
52 | 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x07, 0x00, 0x00,
53 | 0x00, 0x00, 0x80, 0xff, 0xff, 0x00, 0x00, 0x00 };
54 |
55 |
56 | const uint8_t batteryBits[] PROGMEM = {
57 | 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x07, 0xff, 0xff, 0xff, 0xff, 0xff,
58 | 0xff, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0xf3, 0x07, 0x00,
59 | 0x10, 0x00, 0x00, 0x06, 0x0b, 0x08, 0x00, 0x30, 0x00, 0x00, 0x06, 0x0b,
60 | 0x88, 0x00, 0x70, 0x00, 0x00, 0xfe, 0x0b, 0x88, 0x01, 0xd0, 0x00, 0x00,
61 | 0xfe, 0x0b, 0x88, 0x03, 0xd0, 0x01, 0x00, 0xc6, 0x0b, 0x8a, 0x06, 0x50,
62 | 0x03, 0x00, 0xc6, 0x0b, 0x09, 0x0d, 0xd0, 0x06, 0x00, 0xc6, 0x8b, 0x08,
63 | 0x1a, 0x50, 0x0d, 0x00, 0xc6, 0x4b, 0x08, 0x34, 0x50, 0x1a, 0x00, 0xc6,
64 | 0x2b, 0x08, 0x68, 0x50, 0x34, 0x00, 0xc6, 0x0b, 0x0a, 0xd0, 0x50, 0x68,
65 | 0x00, 0xc6, 0x0b, 0x09, 0xa0, 0x51, 0xd0, 0x00, 0xc6, 0x8b, 0x08, 0x40,
66 | 0x53, 0xa0, 0x01, 0xc6, 0x4b, 0x08, 0x80, 0x56, 0x40, 0x03, 0xc6, 0x2b,
67 | 0x08, 0x00, 0x5d, 0x80, 0x06, 0xc6, 0x0b, 0x08, 0x00, 0x5a, 0x00, 0x0d,
68 | 0xc6, 0x0b, 0x08, 0x00, 0x74, 0x00, 0x0a, 0xfe, 0x0b, 0x08, 0x00, 0x68,
69 | 0x00, 0x0c, 0xfe, 0x0b, 0x08, 0x00, 0x50, 0x00, 0x08, 0x06, 0x0b, 0x04,
70 | 0x00, 0x60, 0x00, 0x00, 0x06, 0xf3, 0x07, 0x00, 0x40, 0x00, 0x00, 0x06,
71 | 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0xff, 0xff, 0xff, 0xff, 0xff,
72 | 0xff, 0x07, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x07 };
73 |
74 |
75 | const uint8_t faceHappyBits[] PROGMEM = {
76 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
77 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xff, 0xff, 0x3f,
78 | 0x00, 0x00, 0xf8, 0xff, 0xff, 0x01, 0xc0, 0xff, 0xff, 0x7f, 0x00, 0x00,
79 | 0xfc, 0xff, 0xff, 0x03, 0xe0, 0xff, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff,
80 | 0xff, 0x07, 0xe0, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x07,
81 | 0x60, 0x00, 0x00, 0xc0, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00,
82 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x00,
83 | 0x00, 0x00, 0x00, 0xf0, 0x03, 0x00, 0x00, 0xc0, 0x7f, 0x00, 0x00, 0x00,
84 | 0x00, 0xfc, 0x0f, 0x00, 0x00, 0xf0, 0xff, 0x01, 0x00, 0x00, 0x00, 0xff,
85 | 0x3f, 0x00, 0x00, 0xf8, 0xff, 0x01, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
86 | 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x7f, 0x00, 0x00, 0xfc,
87 | 0xff, 0x07, 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07,
88 | 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00,
89 | 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff,
90 | 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01,
91 | 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe,
92 | 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f,
93 | 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00,
94 | 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00, 0x80, 0xff,
95 | 0x7f, 0x00, 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
96 | 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x00, 0xff, 0x1f, 0x00, 0x00, 0xf0,
97 | 0xff, 0x01, 0x00, 0x00, 0x00, 0xfc, 0x0f, 0x00, 0x00, 0xc0, 0x7f, 0x00,
98 | 0x00, 0x00, 0x00, 0xf0, 0x03, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00,
99 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
100 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
101 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
102 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
103 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
104 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
105 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
106 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
107 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
108 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00,
109 | 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
110 | 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
111 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x3e,
112 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf8, 0x00, 0x00, 0xfe, 0x03, 0x00,
113 | 0x00, 0x00, 0x00, 0x00, 0xff, 0x00, 0x00, 0xfe, 0x1f, 0x00, 0x00, 0x00,
114 | 0x00, 0xf0, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x00, 0x00, 0x00, 0x00, 0xfe,
115 | 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00,
116 | 0x00, 0xce, 0xff, 0xff, 0x01, 0x00, 0xfe, 0xff, 0xef, 0x00, 0x00, 0x0e,
117 | 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xe0, 0x00, 0x00, 0x0e, 0xf0, 0xff,
118 | 0xff, 0xff, 0xff, 0x1f, 0xe0, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff,
119 | 0xff, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf8, 0xff, 0xff, 0x3f, 0x00,
120 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0x01, 0x00, 0x00, 0x00,
121 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
122 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
123 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
124 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
125 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
126 |
127 | const uint8_t faceNormalBits[] PROGMEM = {
128 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
129 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0xff, 0xff, 0xff,
130 | 0x00, 0x00, 0xfe, 0xff, 0xff, 0x07, 0xe0, 0xff, 0xff, 0xff, 0x00, 0x00,
131 | 0xfe, 0xff, 0xff, 0x07, 0xe0, 0xff, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff,
132 | 0xff, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
133 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
134 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x00,
135 | 0x00, 0x00, 0x00, 0xf0, 0x03, 0x00, 0x00, 0xc0, 0x7f, 0x00, 0x00, 0x00,
136 | 0x00, 0xfc, 0x0f, 0x00, 0x00, 0xf0, 0xff, 0x01, 0x00, 0x00, 0x00, 0xff,
137 | 0x3f, 0x00, 0x00, 0xf8, 0xff, 0x01, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
138 | 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x7f, 0x00, 0x00, 0xfc,
139 | 0xff, 0x07, 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07,
140 | 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00,
141 | 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff,
142 | 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01,
143 | 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe,
144 | 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x01, 0x00, 0xfe, 0xff, 0x0f,
145 | 0x00, 0x00, 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00,
146 | 0xc0, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00, 0x80, 0xff,
147 | 0x7f, 0x00, 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
148 | 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x00, 0xff, 0x1f, 0x00, 0x00, 0xf0,
149 | 0xff, 0x01, 0x00, 0x00, 0x00, 0xfc, 0x0f, 0x00, 0x00, 0xc0, 0x7f, 0x00,
150 | 0x00, 0x00, 0x00, 0xf0, 0x03, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00,
151 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
152 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
153 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
154 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
155 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
156 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
157 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
158 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
159 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
160 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00,
161 | 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
162 | 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
163 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e,
164 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0xfe, 0xff, 0xff,
165 | 0xff, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0xff, 0xff, 0xff,
166 | 0xff, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
167 | 0xff, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
168 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e,
169 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00,
170 | 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
171 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
172 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
173 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
174 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
175 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
176 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
177 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
178 |
179 |
180 | const uint8_t faceConfusedBits[] PROGMEM = {
181 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
182 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x01, 0x00, 0x00,
183 | 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0xe0, 0x0f, 0x00, 0x00, 0x00, 0x00,
184 | 0x00, 0x00, 0xfc, 0x01, 0xf0, 0xff, 0x03, 0x00, 0x00, 0x00, 0x00, 0xc0,
185 | 0xff, 0x03, 0xf0, 0xff, 0xff, 0x01, 0x00, 0x00, 0x00, 0xfe, 0xff, 0x07,
186 | 0xf8, 0xff, 0xff, 0x07, 0x00, 0x00, 0xc0, 0xff, 0xff, 0x07, 0xf8, 0xff,
187 | 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff, 0xff, 0x0f, 0xfc, 0xff, 0xff, 0xff,
188 | 0x07, 0x80, 0xff, 0xff, 0xff, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
189 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
190 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
191 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc,
192 | 0xff, 0x07, 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x08, 0xfc, 0xff, 0x07,
193 | 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x18, 0xfe, 0xff, 0x0f, 0x00, 0x00,
194 | 0xe0, 0xff, 0xff, 0x00, 0x18, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff,
195 | 0xff, 0x00, 0x18, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00,
196 | 0x18, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00, 0x18, 0xfe,
197 | 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00, 0x18, 0xfe, 0xff, 0x0f,
198 | 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x18, 0xfc, 0xff, 0x07, 0x00, 0x00,
199 | 0xc0, 0xff, 0x7f, 0x00, 0x3c, 0xfc, 0xff, 0x07, 0x00, 0x00, 0x80, 0xff,
200 | 0x7f, 0x00, 0x3c, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
201 | 0x3c, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x00, 0xff, 0x1f, 0x00, 0x3c, 0xf0,
202 | 0xff, 0x01, 0x00, 0x00, 0x00, 0xfc, 0x0f, 0x00, 0x18, 0xc0, 0x7f, 0x00,
203 | 0x00, 0x00, 0x00, 0xf0, 0x01, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00,
204 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
205 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
206 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
207 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
208 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
209 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
210 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
211 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
212 | 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20,
213 | 0x00, 0xc0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x70, 0x00, 0xe0,
214 | 0x03, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0xf8, 0x00, 0xf0, 0x07, 0x00,
215 | 0xe0, 0x00, 0x00, 0x0e, 0x00, 0xfc, 0x00, 0x78, 0x07, 0x00, 0xe0, 0x00,
216 | 0x00, 0x0e, 0x00, 0xfe, 0x01, 0x3c, 0x0f, 0x00, 0xe0, 0x00, 0x00, 0x0e,
217 | 0x00, 0xdf, 0x01, 0x1e, 0x1e, 0x00, 0xe0, 0x00, 0x00, 0xfe, 0xff, 0x8f,
218 | 0x03, 0x0f, 0x1c, 0xe0, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x87, 0x87, 0x07,
219 | 0x38, 0xf0, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x03, 0xc7, 0x03, 0x38, 0xf8,
220 | 0xff, 0x00, 0x00, 0x0e, 0x00, 0x00, 0xef, 0x01, 0x70, 0x3c, 0xe0, 0x00,
221 | 0x00, 0x0e, 0x00, 0x00, 0xfe, 0x00, 0xf0, 0x1e, 0xe0, 0x00, 0x00, 0x0e,
222 | 0x00, 0x00, 0x7e, 0x00, 0xe0, 0x0f, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00,
223 | 0x7c, 0x00, 0xc0, 0x07, 0xe0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00,
224 | 0xc0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
225 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
226 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
227 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
228 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
229 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
230 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
231 |
232 |
233 | const uint8_t faceDisappointedBits[] PROGMEM = {
234 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
235 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
236 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
237 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
238 | 0x00, 0x00, 0xc0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
239 | 0xe0, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0x01, 0xf0, 0xff,
240 | 0x03, 0x00, 0x00, 0x00, 0x00, 0xc0, 0xff, 0x03, 0xf0, 0xff, 0xff, 0x01,
241 | 0x00, 0x00, 0x00, 0xfe, 0xff, 0x07, 0xf8, 0xff, 0xff, 0x07, 0x00, 0x00,
242 | 0xc0, 0xff, 0xff, 0x07, 0xf8, 0xff, 0xff, 0xff, 0x00, 0x00, 0xfc, 0xff,
243 | 0xff, 0x0f, 0xfc, 0xff, 0xff, 0xff, 0x07, 0x80, 0xff, 0xff, 0xff, 0x1f,
244 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc,
245 | 0xff, 0x07, 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x00, 0xfc, 0xff, 0x07,
246 | 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00,
247 | 0xe0, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff,
248 | 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00,
249 | 0x00, 0xfe, 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00, 0x00, 0xfe,
250 | 0xff, 0x0f, 0x00, 0x00, 0xe0, 0xff, 0xff, 0x00, 0x00, 0xfe, 0xff, 0x0f,
251 | 0x00, 0x00, 0xc0, 0xff, 0x7f, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00,
252 | 0xc0, 0xff, 0x7f, 0x00, 0x00, 0xfc, 0xff, 0x07, 0x00, 0x00, 0x80, 0xff,
253 | 0x7f, 0x00, 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x80, 0xff, 0x3f, 0x00,
254 | 0x00, 0xf8, 0xff, 0x03, 0x00, 0x00, 0x00, 0xff, 0x1f, 0x00, 0x00, 0xf0,
255 | 0xff, 0x01, 0x00, 0x00, 0x00, 0xfc, 0x0f, 0x00, 0x00, 0xc0, 0x7f, 0x00,
256 | 0x00, 0x00, 0x00, 0xf0, 0x01, 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00,
257 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
258 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
259 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
260 | 0x00, 0x00, 0x00, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
261 | 0xc0, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0xff,
262 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf8, 0xf1, 0x03, 0x00,
263 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0xc0, 0x0f, 0x00, 0x00, 0x00,
264 | 0x00, 0x00, 0x00, 0x80, 0x1f, 0x80, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00,
265 | 0x00, 0xe0, 0x0f, 0x00, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf8,
266 | 0x03, 0x00, 0xf8, 0x01, 0x00, 0x00, 0x00, 0x0e, 0x00, 0xfe, 0x00, 0x00,
267 | 0xf0, 0x03, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x3f, 0x00, 0x00, 0xc0, 0x0f,
268 | 0xe0, 0x00, 0x00, 0x0e, 0xc0, 0x0f, 0x00, 0x00, 0x00, 0x3f, 0xe0, 0x00,
269 | 0x00, 0x0e, 0xf0, 0x03, 0x00, 0x00, 0x00, 0x7e, 0xe0, 0x00, 0x00, 0x0e,
270 | 0xfc, 0x00, 0x00, 0x00, 0x00, 0xf8, 0xe1, 0x00, 0x00, 0xfe, 0x7f, 0x00,
271 | 0x00, 0x00, 0x00, 0xe0, 0xff, 0x00, 0x00, 0xfe, 0x1f, 0x00, 0x00, 0x00,
272 | 0x00, 0x80, 0xff, 0x00, 0x00, 0xfe, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00,
273 | 0xff, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00,
274 | 0x00, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e,
275 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x0e, 0x00, 0x00,
276 | 0x00, 0x00, 0x00, 0x00, 0xe0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
277 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
278 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
279 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
280 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
281 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
282 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
283 | 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
284 |
285 |
286 |
287 | const char controlHtml[] PROGMEM = R"=====(
288 |
289 |
290 |
291 |
292 | Balancig robot
293 |
294 |
295 |
296 |
301 |
302 |
345 |
346 | )=====";
347 |
348 |
349 | const char settingsHtml[] PROGMEM = R"=====(
350 |
351 |
352 |
353 |
354 | Balancig robot
355 |
356 |
357 |
358 |
363 |
364 |
365 |
PID settings:
366 |