AP_OSD: add primary airspeed item

and fix param description
This commit is contained in:
vierfuffzig 2019-07-21 10:48:16 +02:00 committed by Randy Mackay
parent 71533c7c5c
commit 6b1046f0ac
2 changed files with 33 additions and 0 deletions

View File

@ -88,6 +88,7 @@ private:
AP_OSD_Setting compass{true, 15, 3};
AP_OSD_Setting wind{false, 2, 12};
AP_OSD_Setting aspeed{false, 2, 13};
AP_OSD_Setting aspd1{false, 0, 0};
AP_OSD_Setting aspd2{false, 0, 0};
AP_OSD_Setting vspeed{true, 24, 9};
@ -147,6 +148,7 @@ private:
void draw_compass(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_aspd1(uint8_t x, uint8_t y);
void draw_aspd2(uint8_t x, uint8_t y);
void draw_vspeed(uint8_t x, uint8_t y);

View File

@ -672,6 +672,22 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Range: 0 15
AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting),
// @Param: ASPD1_EN
// @DisplayName: ASPD1_EN
// @Description: Displays airspeed reported directly from primary airspeed sensor
// @Values: 0:Disabled,1:Enabled
// @Param: ASPD1_X
// @DisplayName: ASPD1_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: ASPD1_Y
// @DisplayName: ASPD1_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
AP_GROUPEND
};
@ -1464,6 +1480,20 @@ void AP_OSD_Screen::draw_bat2used(uint8_t x, uint8_t y)
draw_batused(1, x, y);
}
void AP_OSD_Screen::draw_aspd1(uint8_t x, uint8_t y)
{
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
if (!airspeed) {
return;
}
float asp1 = airspeed->get_airspeed();
if (airspeed != nullptr && airspeed->healthy()) {
backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, asp1), u_icon(SPEED));
} else {
backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
}
}
void AP_OSD_Screen::draw_aspd2(uint8_t x, uint8_t y)
{
AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
@ -1505,6 +1535,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(fltmode);
DRAW_SETTING(gspeed);
DRAW_SETTING(aspeed);
DRAW_SETTING(aspd1);
DRAW_SETTING(aspd2);
DRAW_SETTING(vspeed);
DRAW_SETTING(throttle);