AP_OSD: add secondary airspeed item

This commit is contained in:
vierfuffzig 2018-09-11 19:31:07 +02:00 committed by Andrew Tridgell
parent a083d98b96
commit 5a262a7f6a
2 changed files with 18 additions and 0 deletions

View File

@ -88,6 +88,7 @@ private:
AP_OSD_Setting compass{true, 15, 3}; AP_OSD_Setting compass{true, 15, 3};
AP_OSD_Setting wind{false, 2, 12}; AP_OSD_Setting wind{false, 2, 12};
AP_OSD_Setting aspeed{false, 2, 13}; AP_OSD_Setting aspeed{false, 2, 13};
AP_OSD_Setting aspd2{false, 0, 0};
AP_OSD_Setting vspeed{true, 24, 9}; AP_OSD_Setting vspeed{true, 24, 9};
#ifdef HAVE_AP_BLHELI_SUPPORT #ifdef HAVE_AP_BLHELI_SUPPORT
@ -145,6 +146,7 @@ private:
void draw_compass(uint8_t x, uint8_t y); void draw_compass(uint8_t x, uint8_t y);
void draw_wind(uint8_t x, uint8_t y); void draw_wind(uint8_t x, uint8_t y);
void draw_aspeed(uint8_t x, uint8_t y); void draw_aspeed(uint8_t x, uint8_t y);
void draw_aspd2(uint8_t x, uint8_t y);
void draw_vspeed(uint8_t x, uint8_t y); void draw_vspeed(uint8_t x, uint8_t y);
//helper functions //helper functions

View File

@ -206,6 +206,10 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Path: AP_OSD_Setting.cpp // @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting), AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting),
// @Group: ASPD2
// @Path: AP_OSD_Setting.cpp
AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting),
AP_GROUPEND AP_GROUPEND
}; };
@ -966,6 +970,17 @@ void AP_OSD_Screen::draw_bat2used(uint8_t x, uint8_t y)
} }
} }
void AP_OSD_Screen::draw_aspd2(uint8_t x, uint8_t y)
{
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
float asp2 = airspeed->get_airspeed(1);
if (airspeed != nullptr && airspeed->healthy(1)) {
backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, asp2), u_icon(SPEED));
} else {
backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
}
}
#define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos) #define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)
void AP_OSD_Screen::draw(void) void AP_OSD_Screen::draw(void)
@ -993,6 +1008,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(fltmode); DRAW_SETTING(fltmode);
DRAW_SETTING(gspeed); DRAW_SETTING(gspeed);
DRAW_SETTING(aspeed); DRAW_SETTING(aspeed);
DRAW_SETTING(aspd2);
DRAW_SETTING(vspeed); DRAW_SETTING(vspeed);
DRAW_SETTING(throttle); DRAW_SETTING(throttle);
DRAW_SETTING(heading); DRAW_SETTING(heading);