mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
AP_OSD: add ground speed item
This commit is contained in:
parent
fcd351b5c0
commit
aeaf695d83
@ -71,6 +71,7 @@ private:
|
|||||||
AP_OSD_Setting sats{true, 1, 4};
|
AP_OSD_Setting sats{true, 1, 4};
|
||||||
AP_OSD_Setting fltmode{true, 12, 14};
|
AP_OSD_Setting fltmode{true, 12, 14};
|
||||||
AP_OSD_Setting message{false, 0, 0};
|
AP_OSD_Setting message{false, 0, 0};
|
||||||
|
AP_OSD_Setting gspeed{false, 0, 0};
|
||||||
|
|
||||||
void draw_altitude(uint8_t x, uint8_t y);
|
void draw_altitude(uint8_t x, uint8_t y);
|
||||||
void draw_bat_volt(uint8_t x, uint8_t y);
|
void draw_bat_volt(uint8_t x, uint8_t y);
|
||||||
@ -80,6 +81,7 @@ private:
|
|||||||
void draw_sats(uint8_t x, uint8_t y);
|
void draw_sats(uint8_t x, uint8_t y);
|
||||||
void draw_fltmode(uint8_t x, uint8_t y);
|
void draw_fltmode(uint8_t x, uint8_t y);
|
||||||
void draw_message(uint8_t x, uint8_t y);
|
void draw_message(uint8_t x, uint8_t y);
|
||||||
|
void draw_gspeed(uint8_t x, uint8_t y);
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_OSD {
|
class AP_OSD {
|
||||||
|
@ -84,6 +84,10 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||||||
// @Path: AP_OSD_Setting.cpp
|
// @Path: AP_OSD_Setting.cpp
|
||||||
AP_SUBGROUPINFO(message, "MESSAGE", 11, AP_OSD_Screen, AP_OSD_Setting),
|
AP_SUBGROUPINFO(message, "MESSAGE", 11, AP_OSD_Screen, AP_OSD_Setting),
|
||||||
|
|
||||||
|
// @Group: GSPEED
|
||||||
|
// @Path: AP_OSD_Setting.cpp
|
||||||
|
AP_SUBGROUPINFO(gspeed, "GSPEED", 12, AP_OSD_Screen, AP_OSD_Setting),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -106,6 +110,7 @@ AP_OSD_Screen::AP_OSD_Screen()
|
|||||||
#define SYM_VOLT 0x06
|
#define SYM_VOLT 0x06
|
||||||
#define SYM_AMP 0x9A
|
#define SYM_AMP 0x9A
|
||||||
#define SYM_MAH 0x07
|
#define SYM_MAH 0x07
|
||||||
|
#define SYM_KMH 0xA1
|
||||||
|
|
||||||
#define SYM_SAT_L 0x1E
|
#define SYM_SAT_L 0x1E
|
||||||
#define SYM_SAT_R 0x1F
|
#define SYM_SAT_R 0x1F
|
||||||
@ -184,6 +189,13 @@ void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
|
||||||
|
{
|
||||||
|
AP_GPS & gps = AP::gps();
|
||||||
|
float v = gps.ground_speed() * 3.6;
|
||||||
|
backend->write(x, y, false, "%3.0f%c", v, SYM_KMH);
|
||||||
|
}
|
||||||
|
|
||||||
#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)
|
||||||
@ -200,4 +212,5 @@ void AP_OSD_Screen::draw(void)
|
|||||||
DRAW_SETTING(sats);
|
DRAW_SETTING(sats);
|
||||||
DRAW_SETTING(fltmode);
|
DRAW_SETTING(fltmode);
|
||||||
DRAW_SETTING(message);
|
DRAW_SETTING(message);
|
||||||
|
DRAW_SETTING(gspeed);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user