AP_OSD: refactoring based on review suggestions

This commit is contained in:
Alexander Malishev 2018-07-09 02:32:29 +04:00 committed by Andrew Tridgell
parent e364a815f8
commit ac71a181d6
6 changed files with 126 additions and 76 deletions

View File

@ -73,7 +73,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Param: _OPTIONS
// @DisplayName: OSD Options
// @Description: This sets options that change the display
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll, 3:ImperialUnits
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll
// @User: Standard
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
@ -89,6 +89,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Description: Sets vertical offset of the osd inside image
// @Range: 0 31
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("_V_OFFSET", 10, AP_OSD, v_offset, 16),
// @Param: _H_OFFSET
@ -96,6 +97,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Description: Sets horizontal offset of the osd inside image
// @Range: 0 63
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("_H_OFFSET", 11, AP_OSD, h_offset, 32),
// @Param: _W_RSSI
@ -103,21 +105,21 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Description: Set level at which RSSI item will flash
// @Range: 0 99
// @User: Standard
AP_GROUPINFO("_W_RSSI", 11, AP_OSD, warn_rssi, 30),
AP_GROUPINFO("_W_RSSI", 12, AP_OSD, warn_rssi, 30),
// @Param: _W_NSAT
// @DisplayName: NSAT warn leve
// @DisplayName: NSAT warn level
// @Description: Set level at which NSAT item will flash
// @Range: 1 30
// @User: Standard
AP_GROUPINFO("_W_NSAT", 12, AP_OSD, warn_nsat, 9),
AP_GROUPINFO("_W_NSAT", 13, AP_OSD, warn_nsat, 9),
// @Param: _W_BATVOLT
// @DisplayName: BAT_VOLT warn level
// @Description: Set level at which BAT_VOLT item will flash
// @Range: 0 100
// @User: Standard
AP_GROUPINFO("_W_BATVOLT", 13, AP_OSD, warn_batvolt, 10.0f),
AP_GROUPINFO("_W_BATVOLT", 14, AP_OSD, warn_batvolt, 10.0f),
AP_GROUPEND
};
@ -185,7 +187,6 @@ void AP_OSD::update_osd()
update_current_screen();
screen[current_screen].set_osd(this);
screen[current_screen].set_backend(backend);
screen[current_screen].draw();

View File

@ -51,15 +51,7 @@ public:
void draw(void);
void set_backend(AP_OSD_Backend *_backend)
{
backend = _backend;
};
void set_osd(AP_OSD *_osd)
{
osd = _osd;
};
void set_backend(AP_OSD_Backend *_backend);
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
@ -109,6 +101,11 @@ private:
AP_OSD_Setting gps_latitude{true, 9, 13};
AP_OSD_Setting gps_longitude{true, 9, 14};
bool check_option(uint32_t option);
char u_icon(uint16_t unit_type);
float u_scale(uint16_t unit_type, float value);
void draw_altitude(uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t x, uint8_t y);
void draw_rssi(uint8_t x, uint8_t y);
@ -127,7 +124,9 @@ private:
void draw_aspeed(uint8_t x, uint8_t y);
void draw_vspeed(uint8_t x, uint8_t y);
//helper functions
void draw_speed_vector(uint8_t x, uint8_t y, Vector2f v, int32_t yaw);
void draw_distance(uint8_t x, uint8_t y, float distance);
#ifdef HAVE_AP_BLHELI_SUPPORT
void draw_blh_temp(uint8_t x, uint8_t y);
@ -137,6 +136,17 @@ private:
void draw_gps_latitude(uint8_t x, uint8_t y);
void draw_gps_longitude(uint8_t x, uint8_t y);
enum {
ALTITUDE=0,
SPEED=1,
VSPEED=2,
DISTANCE=3,
DISTANCE_LONG=4,
TEMPERATURE=5,
UNIT_LAST=6,
};
};
class AP_OSD {
@ -181,11 +191,18 @@ public:
OPTION_DECIMAL_PACK = 1U<<0,
OPTION_INVERTED_WIND = 1U<<1,
OPTION_INVERTED_AH_ROLL = 1U<<2,
OPTION_IMPERIAL_UNITS = 1U<<3,
};
AP_Int32 options;
enum {
UNITS_METRIC=0,
UNITS_IMPERIAL=1,
UNITS_LAST=2,
};
AP_Int8 units;
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
private:

View File

@ -49,6 +49,11 @@ public:
INVERT = (1 << 3),
};
AP_OSD * get_osd()
{
return &_osd;
}
protected:
AP_OSD& _osd;

View File

@ -90,7 +90,7 @@ void AP_OSD_SITL::load_font(void)
p[3] = 255;
break;
}
}
}
font[i].update(pixels);
@ -137,13 +137,12 @@ void AP_OSD_SITL::update_thread(void)
}
uint8_t blink = 0;
while (w->isOpen())
{
while (w->isOpen()) {
sf::Event event;
while (w->pollEvent(event))
{
if (event.type == sf::Event::Closed)
while (w->pollEvent(event)) {
if (event.type == sf::Event::Closed) {
w->close();
}
}
if (counter == last_counter) {
usleep(10000);
@ -176,7 +175,7 @@ void AP_OSD_SITL::update_thread(void)
w->draw(s);
}
}
blink = (blink+1) % 4;
w->display();
if (last_font != get_font_num()) {

View File

@ -60,7 +60,7 @@ private:
// scaling factor to make it easier to read
static const uint8_t char_scale = 2;
uint8_t buffer[video_lines][video_cols];
uint8_t attr[video_lines][video_cols];

View File

@ -219,24 +219,59 @@ AP_OSD_Screen::AP_OSD_Screen()
#define SYM_GPS_LAT 0xA6
#define SYM_GPS_LONG 0xA7
//units convertion
#define M_TO_FT(x) (3.28084f*(x))
#define M_TO_MI(x) ((x)/1609.34f)
#define M_TO_KM(x) ((x)/1000.0f)
#define MS_TO_KMH(x) (3.6f*(x))
#define MS_TO_MPH(x) (2.23694f*(x))
#define MS_TO_FS(x) (3.28084f*(x))
void AP_OSD_Screen::set_backend(AP_OSD_Backend *_backend)
{
backend = _backend;
osd = _backend->get_osd();
};
bool AP_OSD_Screen::check_option(uint32_t option)
{
return (osd->options & option) != 0;
}
char AP_OSD_Screen::u_icon(uint16_t unit)
{
static const char icons[UNIT_LAST][AP_OSD::UNITS_LAST] = {
{(char)SYM_ALT_M, (char)SYM_ALT_FT}, //ALTITUDE
{(char)SYM_KMH, (char)SYM_MPH}, //SPEED
{(char)SYM_MS, (char)SYM_FS}, //VSPEED
{(char)SYM_M, (char)SYM_FT}, //DISTANCE
{(char)SYM_KM, (char)SYM_MI}, //DISTANCE_LONG
{(char)SYM_DEGREES_C, (char)SYM_DEGREES_F}//TEMPERATURE
};
return icons[unit][osd->units];
}
float AP_OSD_Screen::u_scale(uint16_t unit, float value)
{
static const float scale[UNIT_LAST][AP_OSD::UNITS_LAST] = {
{1.0f, 3.28084f}, //ALTITUDE
{3.6f, 2.23694f}, //SPEED
{1.0f, 3.28084f}, //VSPEED
{1.0f, 3.28084f}, //DISTANCE
{1.0f/1000.0f, 1.0f/1609.34f},//DISTANCE_LONG
{1.0f, 1.8f} //TEMPERATURE
};
static const float offset[UNIT_LAST][AP_OSD::UNITS_LAST] = {
{0.0f, 0.0f}, //ALTITUDE
{0.0f, 0.0f}, //SPEED
{0.0f, 0.0f}, //VSPEED
{0.0f, 0.0f}, //DISTANCE
{0.0f, 0.0f}, //DISTANCE_LONG
{0.0f, 32.0f}, //TEMPERATURE
};
return value * scale[unit][osd->units] + offset[unit][osd->units];
}
void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
{
float alt;
AP::ahrs().get_relative_position_D_home(alt);
alt = -alt;
if (osd->options.get() & AP_OSD::OPTION_IMPERIAL_UNITS) {
backend->write(x, y, false, "%4d%c", (int)M_TO_FT(alt), SYM_ALT_FT);
} else {
backend->write(x, y, false, "%4d%c", (int)alt, SYM_ALT_M);
}
backend->write(x, y, false, "%4d%c", (int)u_scale(ALTITUDE, alt), u_icon(ALTITUDE));
}
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
@ -345,11 +380,8 @@ void AP_OSD_Screen::draw_speed_vector(uint8_t x, uint8_t y,Vector2f v, int32_t y
int32_t interval = 36000 / SYM_ARROW_COUNT;
arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
}
if (osd->options.get() & AP_OSD::OPTION_IMPERIAL_UNITS) {
backend->write(x, y, false, "%c%3d%c", arrow, (int)MS_TO_MPH(v_length), SYM_MPH);
} else {
backend->write(x, y, false, "%c%3d%c", arrow, (int)MS_TO_KMH(v_length), SYM_KMH);
}
backend->write(x, y, false, "%c%3d%c", arrow, (int)u_scale(SPEED, v_length), u_icon(SPEED));
}
void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
@ -368,7 +400,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
float pitch = -ahrs.pitch;
//inverted roll AH
if (osd->options.get() & AP_OSD::OPTION_INVERTED_AH_ROLL) {
if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) {
roll = -roll;
}
@ -388,6 +420,28 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
backend->write(x-1,y, false, "%c%c%c", SYM_AH_CENTER_LINE_LEFT, SYM_AH_CENTER, SYM_AH_CENTER_LINE_RIGHT);
}
void AP_OSD_Screen::draw_distance(uint8_t x, uint8_t y, float distance)
{
char unit_icon = u_icon(DISTANCE);
float distance_scaled = u_scale(DISTANCE, distance);
const char *fmt = "%4.0f%c";
if (distance_scaled > 9999.0f) {
distance_scaled = u_scale(DISTANCE_LONG, distance);
unit_icon= u_icon(DISTANCE_LONG);
//try to pack as many useful info as possible
if (distance_scaled<9.0f) {
fmt = "%1.3f%c";
} else if (distance_scaled < 99.0f) {
fmt = "%2.2f%c";
} else if (distance_scaled < 999.0f) {
fmt = "%3.1f%c";
} else {
fmt = "%4.0f%c";
}
}
backend->write(x, y, false, fmt, distance_scaled, unit_icon);
}
void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
{
AP_AHRS &ahrs = AP::ahrs();
@ -402,22 +456,8 @@ void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
angle = 0;
}
char arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
if (osd->options.get() & AP_OSD::OPTION_IMPERIAL_UNITS) {
float distance_in_ft = M_TO_FT(distance);
if (distance_in_ft < 9999.0f) {
backend->write(x, y, false, "%c%c%4d%c", SYM_HOME, arrow, (int)distance_in_ft, SYM_FT);
} else {
backend->write(x, y, false, "%c%c%2.2f%c", SYM_HOME, arrow, M_TO_MI(distance), SYM_MI);
}
} else {
if (distance < 9999.0f) {
backend->write(x, y, false, "%c%c%4d%c", SYM_HOME, arrow, (int)distance, SYM_M);
} else if (distance < 99999.0f) {
backend->write(x, y, false, "%c%c%2.2f%c", SYM_HOME, arrow, M_TO_KM(distance), SYM_KM);
} else {
backend->write(x, y, false, "%c%c%4d%c", SYM_HOME, arrow, (int)M_TO_KM(distance), SYM_KM);
}
}
backend->write(x, y, false, "%c%c", SYM_HOME, arrow);
draw_distance(x+2, y, distance);
} else {
backend->write(x, y, true, "%c", SYM_HOME);
}
@ -472,7 +512,7 @@ void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y)
{
AP_AHRS &ahrs = AP::ahrs();
Vector3f v = ahrs.wind_estimate();
if (osd->options.get() & AP_OSD::OPTION_INVERTED_WIND) {
if (check_option(AP_OSD::OPTION_INVERTED_WIND)) {
v = -v;
}
backend->write(x, y, false, "%c", SYM_WSPD);
@ -483,18 +523,10 @@ void AP_OSD_Screen::draw_aspeed(uint8_t x, uint8_t y)
{
float aspd = 0.0f;
bool have_estimate = AP::ahrs().airspeed_estimate(&aspd);
if (osd->options.get() & AP_OSD::OPTION_IMPERIAL_UNITS) {
if (have_estimate) {
backend->write(x, y, false, "%c%3d%c", SYM_ASPD, (int)MS_TO_MPH(aspd), SYM_MPH);
} else {
backend->write(x, y, false, "%c---%c", SYM_ASPD, SYM_MPH);
}
if (have_estimate) {
backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, aspd), u_icon(SPEED));
} else {
if (have_estimate) {
backend->write(x, y, false, "%c%3d%c", SYM_ASPD, (int)MS_TO_KMH(aspd), SYM_KMH);
} else {
backend->write(x, y, false, "%c---%c", SYM_ASPD, SYM_KMH);
}
backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
}
}
@ -514,11 +546,7 @@ void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y)
sym = SYM_DOWN_DOWN;
}
vspd = fabsf(vspd);
if (osd->options.get() & AP_OSD::OPTION_IMPERIAL_UNITS) {
backend->write(x, y, false, "%c%2d%c", sym, (int)MS_TO_FS(vspd), SYM_FS);
} else {
backend->write(x, y, false, "%c%2d%c", sym, (int)vspd, SYM_MS);
}
backend->write(x, y, false, "%c%2d%c", sym, (int)u_scale(VSPEED, vspd), u_icon(VSPEED));
}
#ifdef HAVE_AP_BLHELI_SUPPORT
@ -535,7 +563,7 @@ void AP_OSD_Screen::draw_blh_temp(uint8_t x, uint8_t y)
// AP_BLHeli & blh = AP_BLHeli::AP_BLHeli();
uint8_t esc_temp = td.temperature;
backend->write(x, y, false, "%3d%c", esc_temp, SYM_DEGREES_C);
backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, esc_temp), u_icon(TEMPERATURE));
}
}