You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
561 lines
17 KiB
561 lines
17 KiB
/* |
|
This program is free software: you can redistribute it and/or modify |
|
it under the terms of the GNU General Public License as published by |
|
the Free Software Foundation, either version 3 of the License, or |
|
(at your option) any later version. |
|
|
|
This program is distributed in the hope that it will be useful, |
|
but WITHOUT ANY WARRANTY; without even the implied warranty of |
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
|
GNU General Public License for more details. |
|
|
|
You should have received a copy of the GNU General Public License |
|
along with this program. If not, see <http://www.gnu.org/licenses/>. |
|
*/ |
|
|
|
/* Notify display driver for 128 x 64 pixel displays */ |
|
#include "Display.h" |
|
|
|
#include "AP_Notify.h" |
|
|
|
#include <stdio.h> // for snprintf |
|
#include <AP_GPS/AP_GPS.h> |
|
|
|
static const uint8_t _font[] = { |
|
0x00, 0x00, 0x00, 0x00, 0x00, |
|
0x3E, 0x5B, 0x4F, 0x5B, 0x3E, |
|
0x3E, 0x6B, 0x4F, 0x6B, 0x3E, |
|
0x1C, 0x3E, 0x7C, 0x3E, 0x1C, |
|
0x18, 0x3C, 0x7E, 0x3C, 0x18, |
|
0x1C, 0x57, 0x7D, 0x57, 0x1C, |
|
0x1C, 0x5E, 0x7F, 0x5E, 0x1C, |
|
0x00, 0x18, 0x3C, 0x18, 0x00, |
|
0xFF, 0xE7, 0xC3, 0xE7, 0xFF, |
|
0x00, 0x18, 0x24, 0x18, 0x00, |
|
0xFF, 0xE7, 0xDB, 0xE7, 0xFF, |
|
0x30, 0x48, 0x3A, 0x06, 0x0E, |
|
0x26, 0x29, 0x79, 0x29, 0x26, |
|
0x40, 0x7F, 0x05, 0x05, 0x07, |
|
0x40, 0x7F, 0x05, 0x25, 0x3F, |
|
0x5A, 0x3C, 0xE7, 0x3C, 0x5A, |
|
0x7F, 0x3E, 0x1C, 0x1C, 0x08, |
|
0x08, 0x1C, 0x1C, 0x3E, 0x7F, |
|
0x14, 0x22, 0x7F, 0x22, 0x14, |
|
0x5F, 0x5F, 0x00, 0x5F, 0x5F, |
|
0x06, 0x09, 0x7F, 0x01, 0x7F, |
|
0x00, 0x66, 0x89, 0x95, 0x6A, |
|
0x60, 0x60, 0x60, 0x60, 0x60, |
|
0x94, 0xA2, 0xFF, 0xA2, 0x94, |
|
0x08, 0x04, 0x7E, 0x04, 0x08, |
|
0x10, 0x20, 0x7E, 0x20, 0x10, |
|
0x08, 0x08, 0x2A, 0x1C, 0x08, |
|
0x08, 0x1C, 0x2A, 0x08, 0x08, |
|
0x1E, 0x10, 0x10, 0x10, 0x10, |
|
0x0C, 0x1E, 0x0C, 0x1E, 0x0C, |
|
0x30, 0x38, 0x3E, 0x38, 0x30, |
|
0x06, 0x0E, 0x3E, 0x0E, 0x06, |
|
0x00, 0x00, 0x00, 0x00, 0x00, |
|
0x00, 0x00, 0x5F, 0x00, 0x00, |
|
0x00, 0x07, 0x00, 0x07, 0x00, |
|
0x14, 0x7F, 0x14, 0x7F, 0x14, |
|
0x24, 0x2A, 0x7F, 0x2A, 0x12, |
|
0x23, 0x13, 0x08, 0x64, 0x62, |
|
0x36, 0x49, 0x56, 0x20, 0x50, |
|
0x00, 0x08, 0x07, 0x03, 0x00, |
|
0x00, 0x1C, 0x22, 0x41, 0x00, |
|
0x00, 0x41, 0x22, 0x1C, 0x00, |
|
0x2A, 0x1C, 0x7F, 0x1C, 0x2A, |
|
0x08, 0x08, 0x3E, 0x08, 0x08, |
|
0x00, 0x80, 0x70, 0x30, 0x00, |
|
0x08, 0x08, 0x08, 0x08, 0x08, |
|
0x00, 0x00, 0x60, 0x60, 0x00, |
|
0x20, 0x10, 0x08, 0x04, 0x02, |
|
0x3E, 0x51, 0x49, 0x45, 0x3E, |
|
0x00, 0x42, 0x7F, 0x40, 0x00, |
|
0x72, 0x49, 0x49, 0x49, 0x46, |
|
0x21, 0x41, 0x49, 0x4D, 0x33, |
|
0x18, 0x14, 0x12, 0x7F, 0x10, |
|
0x27, 0x45, 0x45, 0x45, 0x39, |
|
0x3C, 0x4A, 0x49, 0x49, 0x31, |
|
0x41, 0x21, 0x11, 0x09, 0x07, |
|
0x36, 0x49, 0x49, 0x49, 0x36, |
|
0x46, 0x49, 0x49, 0x29, 0x1E, |
|
0x00, 0x00, 0x14, 0x00, 0x00, |
|
0x00, 0x40, 0x34, 0x00, 0x00, |
|
0x00, 0x08, 0x14, 0x22, 0x41, |
|
0x14, 0x14, 0x14, 0x14, 0x14, |
|
0x00, 0x41, 0x22, 0x14, 0x08, |
|
0x02, 0x01, 0x59, 0x09, 0x06, |
|
0x3E, 0x41, 0x5D, 0x59, 0x4E, |
|
0x7C, 0x12, 0x11, 0x12, 0x7C, |
|
0x7F, 0x49, 0x49, 0x49, 0x36, |
|
0x3E, 0x41, 0x41, 0x41, 0x22, |
|
0x7F, 0x41, 0x41, 0x41, 0x3E, |
|
0x7F, 0x49, 0x49, 0x49, 0x41, |
|
0x7F, 0x09, 0x09, 0x09, 0x01, |
|
0x3E, 0x41, 0x41, 0x51, 0x73, |
|
0x7F, 0x08, 0x08, 0x08, 0x7F, |
|
0x00, 0x41, 0x7F, 0x41, 0x00, |
|
0x20, 0x40, 0x41, 0x3F, 0x01, |
|
0x7F, 0x08, 0x14, 0x22, 0x41, |
|
0x7F, 0x40, 0x40, 0x40, 0x40, |
|
0x7F, 0x02, 0x1C, 0x02, 0x7F, |
|
0x7F, 0x04, 0x08, 0x10, 0x7F, |
|
0x3E, 0x41, 0x41, 0x41, 0x3E, |
|
0x7F, 0x09, 0x09, 0x09, 0x06, |
|
0x3E, 0x41, 0x51, 0x21, 0x5E, |
|
0x7F, 0x09, 0x19, 0x29, 0x46, |
|
0x26, 0x49, 0x49, 0x49, 0x32, |
|
0x03, 0x01, 0x7F, 0x01, 0x03, |
|
0x3F, 0x40, 0x40, 0x40, 0x3F, |
|
0x1F, 0x20, 0x40, 0x20, 0x1F, |
|
0x3F, 0x40, 0x38, 0x40, 0x3F, |
|
0x63, 0x14, 0x08, 0x14, 0x63, |
|
0x03, 0x04, 0x78, 0x04, 0x03, |
|
0x61, 0x59, 0x49, 0x4D, 0x43, |
|
0x00, 0x7F, 0x41, 0x41, 0x41, |
|
0x02, 0x04, 0x08, 0x10, 0x20, |
|
0x00, 0x41, 0x41, 0x41, 0x7F, |
|
0x04, 0x02, 0x01, 0x02, 0x04, |
|
0x40, 0x40, 0x40, 0x40, 0x40, |
|
0x00, 0x03, 0x07, 0x08, 0x00, |
|
0x20, 0x54, 0x54, 0x78, 0x40, |
|
0x7F, 0x28, 0x44, 0x44, 0x38, |
|
0x38, 0x44, 0x44, 0x44, 0x28, |
|
0x38, 0x44, 0x44, 0x28, 0x7F, |
|
0x38, 0x54, 0x54, 0x54, 0x18, |
|
0x00, 0x08, 0x7E, 0x09, 0x02, |
|
0x18, 0xA4, 0xA4, 0x9C, 0x78, |
|
0x7F, 0x08, 0x04, 0x04, 0x78, |
|
0x00, 0x44, 0x7D, 0x40, 0x00, |
|
0x20, 0x40, 0x40, 0x3D, 0x00, |
|
0x7F, 0x10, 0x28, 0x44, 0x00, |
|
0x00, 0x41, 0x7F, 0x40, 0x00, |
|
0x7C, 0x04, 0x78, 0x04, 0x78, |
|
0x7C, 0x08, 0x04, 0x04, 0x78, |
|
0x38, 0x44, 0x44, 0x44, 0x38, |
|
0xFC, 0x18, 0x24, 0x24, 0x18, |
|
0x18, 0x24, 0x24, 0x18, 0xFC, |
|
0x7C, 0x08, 0x04, 0x04, 0x08, |
|
0x48, 0x54, 0x54, 0x54, 0x24, |
|
0x04, 0x04, 0x3F, 0x44, 0x24, |
|
0x3C, 0x40, 0x40, 0x20, 0x7C, |
|
0x1C, 0x20, 0x40, 0x20, 0x1C, |
|
0x3C, 0x40, 0x30, 0x40, 0x3C, |
|
0x44, 0x28, 0x10, 0x28, 0x44, |
|
0x4C, 0x90, 0x90, 0x90, 0x7C, |
|
0x44, 0x64, 0x54, 0x4C, 0x44, |
|
0x00, 0x08, 0x36, 0x41, 0x00, |
|
0x00, 0x00, 0x77, 0x00, 0x00, |
|
0x00, 0x41, 0x36, 0x08, 0x00, |
|
0x02, 0x01, 0x02, 0x04, 0x02, |
|
0x3C, 0x26, 0x23, 0x26, 0x3C, |
|
0x1E, 0xA1, 0xA1, 0x61, 0x12, |
|
0x3A, 0x40, 0x40, 0x20, 0x7A, |
|
0x38, 0x54, 0x54, 0x55, 0x59, |
|
0x21, 0x55, 0x55, 0x79, 0x41, |
|
0x22, 0x54, 0x54, 0x78, 0x42, |
|
0x21, 0x55, 0x54, 0x78, 0x40, |
|
0x20, 0x54, 0x55, 0x79, 0x40, |
|
0x0C, 0x1E, 0x52, 0x72, 0x12, |
|
0x39, 0x55, 0x55, 0x55, 0x59, |
|
0x39, 0x54, 0x54, 0x54, 0x59, |
|
0x39, 0x55, 0x54, 0x54, 0x58, |
|
0x00, 0x00, 0x45, 0x7C, 0x41, |
|
0x00, 0x02, 0x45, 0x7D, 0x42, |
|
0x00, 0x01, 0x45, 0x7C, 0x40, |
|
0x7D, 0x12, 0x11, 0x12, 0x7D, |
|
0xF0, 0x28, 0x25, 0x28, 0xF0, |
|
0x7C, 0x54, 0x55, 0x45, 0x00, |
|
0x20, 0x54, 0x54, 0x7C, 0x54, |
|
0x7C, 0x0A, 0x09, 0x7F, 0x49, |
|
0x32, 0x49, 0x49, 0x49, 0x32, |
|
0x3A, 0x44, 0x44, 0x44, 0x3A, |
|
0x32, 0x4A, 0x48, 0x48, 0x30, |
|
0x3A, 0x41, 0x41, 0x21, 0x7A, |
|
0x3A, 0x42, 0x40, 0x20, 0x78, |
|
0x00, 0x9D, 0xA0, 0xA0, 0x7D, |
|
0x3D, 0x42, 0x42, 0x42, 0x3D, |
|
0x3D, 0x40, 0x40, 0x40, 0x3D, |
|
0x3C, 0x24, 0xFF, 0x24, 0x24, |
|
0x48, 0x7E, 0x49, 0x43, 0x66, |
|
0x2B, 0x2F, 0xFC, 0x2F, 0x2B, |
|
0xFF, 0x09, 0x29, 0xF6, 0x20, |
|
0xC0, 0x88, 0x7E, 0x09, 0x03, |
|
0x20, 0x54, 0x54, 0x79, 0x41, |
|
0x00, 0x00, 0x44, 0x7D, 0x41, |
|
0x30, 0x48, 0x48, 0x4A, 0x32, |
|
0x38, 0x40, 0x40, 0x22, 0x7A, |
|
0x00, 0x7A, 0x0A, 0x0A, 0x72, |
|
0x7D, 0x0D, 0x19, 0x31, 0x7D, |
|
0x26, 0x29, 0x29, 0x2F, 0x28, |
|
0x26, 0x29, 0x29, 0x29, 0x26, |
|
0x30, 0x48, 0x4D, 0x40, 0x20, |
|
0x38, 0x08, 0x08, 0x08, 0x08, |
|
0x08, 0x08, 0x08, 0x08, 0x38, |
|
0x2F, 0x10, 0xC8, 0xAC, 0xBA, |
|
0x2F, 0x10, 0x28, 0x34, 0xFA, |
|
0x00, 0x00, 0x7B, 0x00, 0x00, |
|
0x08, 0x14, 0x2A, 0x14, 0x22, |
|
0x22, 0x14, 0x2A, 0x14, 0x08, |
|
0x55, 0x00, 0x55, 0x00, 0x55, |
|
0xAA, 0x55, 0xAA, 0x55, 0xAA, |
|
0xFF, 0x55, 0xFF, 0x55, 0xFF, |
|
0x00, 0x00, 0x00, 0xFF, 0x00, |
|
0x10, 0x10, 0x10, 0xFF, 0x00, |
|
0x14, 0x14, 0x14, 0xFF, 0x00, |
|
0x10, 0x10, 0xFF, 0x00, 0xFF, |
|
0x10, 0x10, 0xF0, 0x10, 0xF0, |
|
0x14, 0x14, 0x14, 0xFC, 0x00, |
|
0x14, 0x14, 0xF7, 0x00, 0xFF, |
|
0x00, 0x00, 0xFF, 0x00, 0xFF, |
|
0x14, 0x14, 0xF4, 0x04, 0xFC, |
|
0x14, 0x14, 0x17, 0x10, 0x1F, |
|
0x10, 0x10, 0x1F, 0x10, 0x1F, |
|
0x14, 0x14, 0x14, 0x1F, 0x00, |
|
0x10, 0x10, 0x10, 0xF0, 0x00, |
|
0x00, 0x00, 0x00, 0x1F, 0x10, |
|
0x10, 0x10, 0x10, 0x1F, 0x10, |
|
0x10, 0x10, 0x10, 0xF0, 0x10, |
|
0x00, 0x00, 0x00, 0xFF, 0x10, |
|
0x10, 0x10, 0x10, 0x10, 0x10, |
|
0x10, 0x10, 0x10, 0xFF, 0x10, |
|
0x00, 0x00, 0x00, 0xFF, 0x14, |
|
0x00, 0x00, 0xFF, 0x00, 0xFF, |
|
0x00, 0x00, 0x1F, 0x10, 0x17, |
|
0x00, 0x00, 0xFC, 0x04, 0xF4, |
|
0x14, 0x14, 0x17, 0x10, 0x17, |
|
0x14, 0x14, 0xF4, 0x04, 0xF4, |
|
0x00, 0x00, 0xFF, 0x00, 0xF7, |
|
0x14, 0x14, 0x14, 0x14, 0x14, |
|
0x14, 0x14, 0xF7, 0x00, 0xF7, |
|
0x14, 0x14, 0x14, 0x17, 0x14, |
|
0x10, 0x10, 0x1F, 0x10, 0x1F, |
|
0x14, 0x14, 0x14, 0xF4, 0x14, |
|
0x10, 0x10, 0xF0, 0x10, 0xF0, |
|
0x00, 0x00, 0x1F, 0x10, 0x1F, |
|
0x00, 0x00, 0x00, 0x1F, 0x14, |
|
0x00, 0x00, 0x00, 0xFC, 0x14, |
|
0x00, 0x00, 0xF0, 0x10, 0xF0, |
|
0x10, 0x10, 0xFF, 0x10, 0xFF, |
|
0x14, 0x14, 0x14, 0xFF, 0x14, |
|
0x10, 0x10, 0x10, 0x1F, 0x00, |
|
0x00, 0x00, 0x00, 0xF0, 0x10, |
|
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, |
|
0xF0, 0xF0, 0xF0, 0xF0, 0xF0, |
|
0xFF, 0xFF, 0xFF, 0x00, 0x00, |
|
0x00, 0x00, 0x00, 0xFF, 0xFF, |
|
0x0F, 0x0F, 0x0F, 0x0F, 0x0F, |
|
0x38, 0x44, 0x44, 0x38, 0x44, |
|
0xFC, 0x4A, 0x4A, 0x4A, 0x34, |
|
0x7E, 0x02, 0x02, 0x06, 0x06, |
|
0x02, 0x7E, 0x02, 0x7E, 0x02, |
|
0x63, 0x55, 0x49, 0x41, 0x63, |
|
0x38, 0x44, 0x44, 0x3C, 0x04, |
|
0x40, 0x7E, 0x20, 0x1E, 0x20, |
|
0x06, 0x02, 0x7E, 0x02, 0x02, |
|
0x99, 0xA5, 0xE7, 0xA5, 0x99, |
|
0x1C, 0x2A, 0x49, 0x2A, 0x1C, |
|
0x4C, 0x72, 0x01, 0x72, 0x4C, |
|
0x30, 0x4A, 0x4D, 0x4D, 0x30, |
|
0x30, 0x48, 0x78, 0x48, 0x30, |
|
0xBC, 0x62, 0x5A, 0x46, 0x3D, |
|
0x3E, 0x49, 0x49, 0x49, 0x00, |
|
0x7E, 0x01, 0x01, 0x01, 0x7E, |
|
0x2A, 0x2A, 0x2A, 0x2A, 0x2A, |
|
0x44, 0x44, 0x5F, 0x44, 0x44, |
|
0x40, 0x51, 0x4A, 0x44, 0x40, |
|
0x40, 0x44, 0x4A, 0x51, 0x40, |
|
0x00, 0x00, 0xFF, 0x01, 0x03, |
|
0xE0, 0x80, 0xFF, 0x00, 0x00, |
|
0x08, 0x08, 0x6B, 0x6B, 0x08, |
|
0x36, 0x12, 0x36, 0x24, 0x36, |
|
0x06, 0x0F, 0x09, 0x0F, 0x06, |
|
0x00, 0x00, 0x18, 0x18, 0x00, |
|
0x00, 0x00, 0x10, 0x10, 0x00, |
|
0x30, 0x40, 0xFF, 0x01, 0x01, |
|
0x00, 0x1F, 0x01, 0x01, 0x1E, |
|
0x00, 0x19, 0x1D, 0x17, 0x12, |
|
0x00, 0x3C, 0x3C, 0x3C, 0x3C, |
|
0x00, 0x00, 0x00, 0x00, 0x00 |
|
}; |
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) |
|
static const char * _modename[] = { |
|
"STAB", // STABILIZE = 0, // manual airframe angle with manual throttle |
|
"ACRO", // ACRO = 1, // manual body-frame angular rate with manual throttle |
|
"ALTH", // ALT_HOLD = 2, // manual airframe angle with automatic throttle |
|
"AUTO", // AUTO = 3, // fully automatic waypoint control using mission commands |
|
"GUID", // GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands |
|
"LOIT", // LOITER = 5, // automatic horizontal acceleration with automatic throttle |
|
"RTL ", // RTL = 6, // automatic return to launching point |
|
"CIRC", // CIRCLE = 7, // automatic circular flight with automatic throttle |
|
"----", //8 no mode for copter |
|
"LAND", // LAND = 9, // automatic landing with horizontal position control |
|
"----", //10 no mode for copter |
|
"DRIF", // DRIFT = 11, // semi-automous position, yaw and throttle control |
|
"----", //12 no mode for copter |
|
"SPRT", // SPORT = 13, // manual earth-frame angular rate control with manual throttle |
|
"FLIP", // FLIP = 14, // automatically flip the vehicle on the roll axis |
|
"ATUN", // AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains |
|
"PHLD", // POSHOLD = 16, // automatic position hold with manual override, with automatic throttle |
|
"BRAK", // BRAKE = 17, // full-brake using inertial/GPS system, no pilot input |
|
"THRW", // THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input |
|
"AVOI", // AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft |
|
"GNGP" // GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude |
|
|
|
}; |
|
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) |
|
static const char * _modename[] = { |
|
"MANU", // = 0, |
|
"CIRC", // = 1, |
|
"STAB", // = 2, |
|
"TRAN", // = 3, |
|
"ACRO", // = 4, |
|
"FBWA", // = 5, |
|
"FBWB", // = 6, |
|
"CRUS", // = 7, |
|
"ATUN", // = 8, |
|
"----", //9 no mode for plane |
|
"AUTO", // = 10, |
|
"RTL ", // = 11, |
|
"LOIT", // = 12, |
|
"----", //13 no mode for plane |
|
"----", //14 no mode for plane |
|
"GUID", // = 15, |
|
"INIT", // = 16, |
|
"QSTB", // = 17, |
|
"QHVR", // = 18, |
|
"QLIT", // = 19, |
|
"QLND", // = 20, |
|
"QRTL" // = 21 |
|
}; |
|
#else //rover |
|
static const char * _modename[] = { |
|
"MANU", |
|
"----", |
|
"LERN", |
|
"STER", |
|
"HOLD", |
|
"----", |
|
"----", |
|
"----", |
|
"----", |
|
"----", |
|
"AUTO", |
|
"RTL", |
|
"----", |
|
"----", |
|
"----", |
|
"GUID", |
|
"INIT" |
|
}; |
|
#endif |
|
|
|
bool Display::init(void) |
|
{ |
|
_mstartpos = 0; // ticker shift position |
|
_movedelay = 4; // ticker delay before shifting after new message displayed |
|
|
|
_healthy = hw_init(); |
|
|
|
if (!_healthy) { |
|
return false; |
|
} |
|
|
|
// update all on display |
|
update_all(); |
|
hw_update(); |
|
|
|
return true; |
|
} |
|
|
|
void Display::update() |
|
{ |
|
static uint8_t timer = 0; |
|
static uint8_t screenpage =0; |
|
|
|
// return immediately if not enabled |
|
if (!_healthy) { |
|
return; |
|
} |
|
|
|
// max update frequency 2Hz |
|
if (timer++ < 25) { |
|
return; |
|
} |
|
|
|
timer = 0; |
|
|
|
if (AP_Notify::flags.armed) { |
|
if (screenpage != 1) { |
|
clear_screen(); |
|
update_arm(3); |
|
screenpage = 1; |
|
hw_update(); //update hw once , do not transmition to display in fly |
|
} |
|
return; |
|
} |
|
|
|
|
|
if (screenpage != 2) { |
|
clear_screen(); //once clear screen when page changed |
|
screenpage = 2; |
|
} |
|
|
|
update_all(); |
|
hw_update(); //update at 2 Hz in disarmed mode |
|
|
|
} |
|
|
|
void Display::update_all() |
|
{ |
|
|
|
update_text(0); |
|
update_mode(1); |
|
update_battery(2); |
|
update_gps(3); |
|
//update_gps_sats(4); |
|
update_prearm(4); |
|
update_ekf(5); |
|
} |
|
|
|
void Display::draw_text(uint16_t x, uint16_t y, const char* c) |
|
{ |
|
if (nullptr == c) { |
|
return; |
|
} |
|
while (*c != 0) { |
|
draw_char(x, y, *c); |
|
x += 7; |
|
c++; |
|
} |
|
} |
|
|
|
void Display::draw_char(uint16_t x, uint16_t y, const char c) |
|
{ |
|
uint8_t line; |
|
|
|
// draw char to pixel |
|
for (uint8_t i = 0; i < 6; i++) { |
|
if (i == 5) { |
|
line = 0; |
|
} else { |
|
line = _font[(c * 5) + i]; |
|
} |
|
|
|
for (uint8_t j = 0; j < 8; j++) { |
|
if (line & 1) { |
|
set_pixel(x + i, y + j); |
|
} else { |
|
clear_pixel(x + i, y + j); |
|
} |
|
line >>= 1; |
|
} |
|
} |
|
} |
|
|
|
void Display::update_arm(uint8_t r) |
|
{ |
|
if (AP_Notify::flags.armed) { |
|
draw_text(COLUMN(0), ROW(r), ">>>>> ARMED! <<<<<"); |
|
} else { |
|
draw_text(COLUMN(0), ROW(r), " disarmed "); |
|
} |
|
} |
|
|
|
void Display::update_prearm(uint8_t r) |
|
{ |
|
if (AP_Notify::flags.pre_arm_check) { |
|
draw_text(COLUMN(0), ROW(r), "Prearm: passed "); |
|
} else { |
|
draw_text(COLUMN(0), ROW(r), "Prearm: failed "); |
|
} |
|
} |
|
|
|
void Display::update_gps(uint8_t r) |
|
{ |
|
static const char * gpsfixname[] = {"Other", "NoGPS","NoFix","2D ","3D ","DGPS " ,"RTK "}; |
|
char msg [DISPLAY_MESSAGE_SIZE]; |
|
const char * fixname; |
|
switch (AP_Notify::flags.gps_status) { |
|
case AP_GPS::NO_GPS: |
|
fixname = gpsfixname[1]; |
|
break; |
|
case AP_GPS::NO_FIX: |
|
fixname = gpsfixname[2]; |
|
break; |
|
case AP_GPS::GPS_OK_FIX_2D: |
|
fixname = gpsfixname[3]; |
|
break; |
|
case AP_GPS::GPS_OK_FIX_3D: |
|
fixname = gpsfixname[4]; |
|
break; |
|
case AP_GPS::GPS_OK_FIX_3D_DGPS: |
|
fixname = gpsfixname[5]; |
|
break; |
|
case AP_GPS::GPS_OK_FIX_3D_RTK: |
|
fixname = gpsfixname[6]; |
|
break; |
|
default: |
|
fixname = gpsfixname[0]; |
|
} |
|
snprintf(msg, DISPLAY_MESSAGE_SIZE, "GPS:%s Sats:%u", fixname, AP_Notify::flags.gps_num_sats) ; |
|
draw_text(COLUMN(0), ROW(r), msg); |
|
} |
|
|
|
void Display::update_gps_sats(uint8_t r) |
|
{ |
|
draw_text(COLUMN(0), ROW(r), "Sats:"); |
|
draw_char(COLUMN(8), ROW(r), (AP_Notify::flags.gps_num_sats / 10) + 48); |
|
draw_char(COLUMN(9), ROW(r), (AP_Notify::flags.gps_num_sats % 10) + 48); |
|
} |
|
|
|
void Display::update_ekf(uint8_t r) |
|
{ |
|
if (AP_Notify::flags.ekf_bad) { |
|
draw_text(COLUMN(0), ROW(r), "EKF: fail"); |
|
} else { |
|
draw_text(COLUMN(0), ROW(r), "EKF: ok "); |
|
} |
|
} |
|
|
|
void Display::update_battery(uint8_t r) |
|
{ |
|
char msg [DISPLAY_MESSAGE_SIZE]; |
|
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %4.2fV", AP_Notify::flags.battery_voltage) ; |
|
draw_text(COLUMN(0), ROW(r), msg); |
|
} |
|
void Display::update_mode(uint8_t r) |
|
{ |
|
char msg [DISPLAY_MESSAGE_SIZE]; |
|
snprintf(msg, DISPLAY_MESSAGE_SIZE, "Mode: %s", _modename[AP_Notify::flags.flight_mode]) ; |
|
draw_text(COLUMN(0), ROW(r), msg); |
|
} |
|
|
|
void Display::update_text(uint8_t r) |
|
{ |
|
char msg [DISPLAY_MESSAGE_SIZE]; |
|
char txt [NOTIFY_TEXT_BUFFER_SIZE]; |
|
|
|
snprintf(txt, NOTIFY_TEXT_BUFFER_SIZE, "%s", AP_Notify::get_text()); |
|
_mstartpos++; |
|
for (uint8_t i = 0; i < sizeof(msg); i++) { |
|
if (txt[i + _mstartpos - 1] != 0) { |
|
msg[i] = txt[i + _mstartpos - 1]; |
|
} else { |
|
msg[i] = ' '; |
|
_movedelay = 4; |
|
_mstartpos = 0; |
|
} |
|
} |
|
|
|
if (_mstartpos > sizeof(txt) - sizeof(msg)) { |
|
_mstartpos = 0; |
|
} |
|
if (_movedelay > 0) { |
|
_movedelay--; |
|
_mstartpos = 0; |
|
} |
|
draw_text(COLUMN(0), ROW(0), msg); |
|
}
|
|
|