ArduPilot开源代码之AP_OSD_Screen
1. 源由
在研读《ArduPilot开源代码之AP_OSD》时,重点介绍了各种OSD配置,从DO设备对象的角度入手。
没有重点去阐述关于OSD应用是如何绘制OSD界面图标、信息。在AP_OSD::update_osd
函数中,调用了get_screen(current_screen).draw()
这个OSD界面绘制例程。
本章将重点描述这部分内容,主要涉及 AP_OSD_Screen
和 AP_OSD_AbstractScreen
。
2. AP_OSD_AbstractScreen类
2.1 定义
class AP_OSD_AbstractScreen
{
friend class AP_OSD;
public:
// constructor
AP_OSD_AbstractScreen() {}
virtual void draw(void) {}
void set_backend(AP_OSD_Backend *_backend);
AP_Int8 enabled;
AP_Int16 channel_min;
AP_Int16 channel_max;
protected:
bool check_option(uint32_t option);
#if HAL_WITH_MSP_DISPLAYPORT
virtual uint8_t get_txt_resolution() const {
return 0;
}
virtual uint8_t get_font_index() const {
return 0;
}
#endif
enum unit_type {
ALTITUDE=0,
SPEED=1,
VSPEED=2,
DISTANCE=3,
DISTANCE_LONG=4,
TEMPERATURE=5,
UNIT_TYPE_LAST=6,
};
char u_icon(enum unit_type unit);
float u_scale(enum unit_type unit, float value);
AP_OSD_Backend *backend;
AP_OSD *osd;
static uint8_t symbols_lookup_table[AP_OSD_NUM_SYMBOLS];
};
2.2 关键要点
绘制例程/单位转换/符号表OSD的抽象。
- virtual void draw(void)
用于x,y位置绘制符号和字符串组成的OSD
- 公制/英制/国际标准/航空单位的转换
char u_icon(enum unit_type unit);
float u_scale(enum unit_type unit, float value);
- static uint8_t symbols_lookup_table[AP_OSD_NUM_SYMBOLS]
在
AP_OSD::init_backend
中执行init_symbol_set
加载DO对象的ICON符号表
2.3 重要接口
2.3.1 u_icon
获取单位对应的图标符号index编号。
/*
get the right units icon given a unit
*/
char AP_OSD_AbstractScreen::u_icon(enum unit_type unit)
{
static const uint8_t icons_metric[UNIT_TYPE_LAST] {
SYM_ALT_M, //ALTITUDE
SYM_KMH, //SPEED
SYM_MS, //VSPEED
SYM_M, //DISTANCE
SYM_KM, //DISTANCE_LONG
SYM_DEGREES_C //TEMPERATURE
};
static const uint8_t icons_imperial[UNIT_TYPE_LAST] {
SYM_ALT_FT, //ALTITUDE
SYM_MPH, //SPEED
SYM_FS, //VSPEED
SYM_FT, //DISTANCE
SYM_MI, //DISTANCE_LONG
SYM_DEGREES_F //TEMPERATURE
};
static const uint8_t icons_SI[UNIT_TYPE_LAST] {
SYM_ALT_M, //ALTITUDE
SYM_MS, //SPEED
SYM_MS, //VSPEED
SYM_M, //DISTANCE
SYM_KM, //DISTANCE_LONG
SYM_DEGREES_C //TEMPERATURE
};
static const uint8_t icons_aviation[UNIT_TYPE_LAST] {
SYM_ALT_FT, //ALTITUDE Ft
SYM_KN, //SPEED Knots
SYM_FTMIN, //VSPEED
SYM_FT, //DISTANCE
SYM_NM, //DISTANCE_LONG Nm
SYM_DEGREES_C //TEMPERATURE
};
static const uint8_t* icons[AP_OSD::UNITS_LAST] = {
icons_metric,
icons_imperial,
icons_SI,
icons_aviation,
};
return (char)SYMBOL(icons[constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1)][unit]);
}
2.3.2 u_scale
根据系统选择的单位进制进行scale和offset计算
-
公制 (Metric)
value metric = value \text{value}_{\text{metric}} = \text{value} valuemetric=value -
英制 (Imperial)
value imperial = value × scale_imperial[unit] + offset_imperial[unit] \text{value}_{\text{imperial}} = \text{value} \times \text{scale\_imperial[unit]} + \text{offset\_imperial[unit]} valueimperial=value×scale_imperial[unit]+offset_imperial[unit] -
国际单位制 (SI)
value SI = value \text{value}_{\text{SI}} = \text{value} valueSI=value -
航空单位 (Aviation)
value aviation = value × scale_aviation[unit] \text{value}_{\text{aviation}} = \text{value} \times \text{scale\_aviation[unit]} valueaviation=value×scale_aviation[unit]
/*
scale a value for the user selected units
*/
float AP_OSD_AbstractScreen::u_scale(enum unit_type unit, float value)
{
static const float scale_metric[UNIT_TYPE_LAST] = {
1.0, //ALTITUDE m
3.6, //SPEED km/hr
1.0, //VSPEED m/s
1.0, //DISTANCE m
1.0/1000, //DISTANCE_LONG km
1.0, //TEMPERATURE C
};
static const float scale_imperial[UNIT_TYPE_LAST] = {
3.28084, //ALTITUDE ft
2.23694, //SPEED mph
3.28084, //VSPEED ft/s
3.28084, //DISTANCE ft
1.0/1609.34, //DISTANCE_LONG miles
1.8, //TEMPERATURE F
};
static const float offset_imperial[UNIT_TYPE_LAST] = {
0.0, //ALTITUDE
0.0, //SPEED
0.0, //VSPEED
0.0, //DISTANCE
0.0, //DISTANCE_LONG
32.0, //TEMPERATURE F
};
static const float scale_SI[UNIT_TYPE_LAST] = {
1.0, //ALTITUDE m
1.0, //SPEED m/s
1.0, //VSPEED m/s
1.0, //DISTANCE m
1.0/1000, //DISTANCE_LONG km
1.0, //TEMPERATURE C
};
static const float scale_aviation[UNIT_TYPE_LAST] = {
3.28084, //ALTITUDE Ft
1.94384, //SPEED Knots
196.85, //VSPEED ft/min
3.28084, //DISTANCE ft
0.000539957, //DISTANCE_LONG Nm
1.0, //TEMPERATURE C
};
static const float *scale[AP_OSD::UNITS_LAST] = {
scale_metric,
scale_imperial,
scale_SI,
scale_aviation
};
static const float *offsets[AP_OSD::UNITS_LAST] = {
nullptr,
offset_imperial,
nullptr,
nullptr
};
uint8_t units = constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1);
return value * scale[units][unit] + (offsets[units]?offsets[units][unit]:0);
}
3. AP_OSD_Screen类
3.1 定义
class AP_OSD_Screen : public AP_OSD_AbstractScreen
{
public:
// constructor
AP_OSD_Screen();
// skip the drawing if we are not using a font based backend. This saves a lot of flash space when
// using the MSP OSD system on boards that don't have a MAX7456
#if HAL_WITH_OSD_BITMAP || HAL_WITH_MSP_DISPLAYPORT
void draw(void) override;
#endif
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Param::GroupInfo var_info2[];
#if HAL_WITH_MSP_DISPLAYPORT
uint8_t get_txt_resolution() const override {
return txt_resolution;
}
uint8_t get_font_index() const override {
return font_index;
}
#endif
private:
friend class AP_MSP;
friend class AP_MSP_Telem_Backend;
friend class AP_MSP_Telem_DJI;
static const uint8_t message_visible_width = 26;
static const uint8_t message_scroll_time_ms = 200;
static const uint8_t message_scroll_delay = 5;
static constexpr float ah_max_pitch = DEG_TO_RAD * 20;
//typical fpv camera has 80deg vertical field of view, 16 row of chars
static constexpr float ah_pitch_rad_to_char = 16.0f/(DEG_TO_RAD * 80);
enum class VoltageType {
VOLTAGE,
RESTING_VOLTAGE,
AVG_CELL,
RESTING_CELL,
};
AP_OSD_Setting altitude{true, 23, 8};
AP_OSD_Setting bat_volt{true, 24, 1};
AP_OSD_Setting rssi{true, 1, 1};
AP_OSD_Setting link_quality{false,1,1};
AP_OSD_Setting restvolt{false, 24, 2};
AP_OSD_Setting avgcellvolt{false, 24, 3};
AP_OSD_Setting avgcellrestvolt{false, 24, 4};
AP_OSD_Setting current{true, 25, 2};
AP_OSD_Setting batused{true, 23, 3};
AP_OSD_Setting sats{true, 1, 3};
AP_OSD_Setting fltmode{true, 2, 8};
AP_OSD_Setting message{true, 2, 6};
AP_OSD_Setting gspeed{true, 2, 14};
AP_OSD_Setting horizon{true, 14, 8};
AP_OSD_Setting home{true, 14, 1};
AP_OSD_Setting throttle{true, 24, 11};
AP_OSD_Setting heading{true, 13, 2};
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;
AP_OSD_Setting aspd2;
AP_OSD_Setting vspeed{true, 24, 9};
#if AP_RPM_ENABLED
AP_OSD_Setting rrpm{false, 2, 2};
#endif
#if HAL_WITH_ESC_TELEM
AP_OSD_Setting esc_temp {false, 24, 13};
AP_OSD_Setting esc_rpm{false, 22, 12};
AP_OSD_Setting esc_amps{false, 24, 14};
#endif
AP_OSD_Setting gps_latitude{true, 9, 13};
AP_OSD_Setting gps_longitude{true, 9, 14};
AP_OSD_Setting roll_angle;
AP_OSD_Setting pitch_angle;
AP_OSD_Setting temp;
#if BARO_MAX_INSTANCES > 1
AP_OSD_Setting btemp;
#endif
AP_OSD_Setting hdop;
AP_OSD_Setting waypoint;
AP_OSD_Setting xtrack_error;
AP_OSD_Setting dist{false,22,11};
AP_OSD_Setting stat{false,0,0};
AP_OSD_Setting flightime{false, 23, 10};
AP_OSD_Setting climbeff{false,0,0};
AP_OSD_Setting eff{false, 22, 10};
AP_OSD_Setting atemp;
AP_OSD_Setting bat2_vlt;
AP_OSD_Setting bat2used;
AP_OSD_Setting current2;
AP_OSD_Setting clk;
AP_OSD_Setting callsign;
AP_OSD_Setting vtx_power;
AP_OSD_Setting hgt_abvterr{false, 23, 7};
AP_OSD_Setting fence{false, 14, 9};
AP_OSD_Setting rngf;
#if HAL_PLUSCODE_ENABLE
AP_OSD_Setting pluscode;
#endif
AP_OSD_Setting sidebars{false, 4, 5};
#if AP_OSD_EXTENDED_LNK_STATS
// Extended link stats data panels
AP_OSD_Setting rc_tx_power{false, 25, 12};
AP_OSD_Setting rc_rssi_dbm{false, 6, 2};
AP_OSD_Setting rc_snr{false, 23, 13};
AP_OSD_Setting rc_active_antenna{false, 27, 13};
AP_OSD_Setting rc_lq{false, 18, 2};
#endif
// MSP OSD only
AP_OSD_Setting crosshair;
AP_OSD_Setting home_dist{true, 1, 1};
AP_OSD_Setting home_dir{true, 1, 1};
AP_OSD_Setting power{true, 1, 1};
AP_OSD_Setting cell_volt{true, 1, 1};
AP_OSD_Setting batt_bar{true, 1, 1};
AP_OSD_Setting arming{true, 1, 1};
#if HAL_WITH_MSP_DISPLAYPORT
// Per screen HD resolution options (currently supported only by DisplayPort)
AP_Int8 txt_resolution;
AP_Int8 font_index;
#endif
#if HAL_WITH_ESC_TELEM
AP_Int8 esc_index;
#endif
void draw_altitude(uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t instance,VoltageType type,uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t x, uint8_t y);
void draw_avgcellvolt(uint8_t x, uint8_t y);
void draw_avgcellrestvolt(uint8_t x, uint8_t y);
void draw_restvolt(uint8_t x, uint8_t y);
void draw_rssi(uint8_t x, uint8_t y);
void draw_link_quality(uint8_t x, uint8_t y);
void draw_current(uint8_t x, uint8_t y);
void draw_current(uint8_t instance, uint8_t x, uint8_t y);
void draw_batused(uint8_t x, uint8_t y);
void draw_batused(uint8_t instance, 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_message(uint8_t x, uint8_t y);
void draw_gspeed(uint8_t x, uint8_t y);
void draw_horizon(uint8_t x, uint8_t y);
void draw_home(uint8_t x, uint8_t y);
void draw_throttle(uint8_t x, uint8_t y);
void draw_heading(uint8_t x, uint8_t y);
#if AP_RPM_ENABLED
void draw_rrpm(uint8_t x, uint8_t y);
#endif
#ifdef HAL_OSD_SIDEBAR_ENABLE
void draw_sidebars(uint8_t x, uint8_t y);
#endif
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);
#if HAL_PLUSCODE_ENABLE
void draw_pluscode(uint8_t x, uint8_t y);
#endif
//helper functions
void draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude);
void draw_distance(uint8_t x, uint8_t y, float distance);
char get_arrow_font_index (int32_t angle_cd);
#if HAL_WITH_ESC_TELEM
void draw_esc_temp(uint8_t x, uint8_t y);
void draw_esc_rpm(uint8_t x, uint8_t y);
void draw_esc_amps(uint8_t x, uint8_t y);
#endif
void draw_gps_latitude(uint8_t x, uint8_t y);
void draw_gps_longitude(uint8_t x, uint8_t y);
void draw_roll_angle(uint8_t x, uint8_t y);
void draw_pitch_angle(uint8_t x, uint8_t y);
void draw_temp(uint8_t x, uint8_t y);
#if BARO_MAX_INSTANCES > 1
void draw_btemp(uint8_t x, uint8_t y);
#endif
void draw_hdop(uint8_t x, uint8_t y);
void draw_waypoint(uint8_t x, uint8_t y);
void draw_xtrack_error(uint8_t x, uint8_t y);
void draw_dist(uint8_t x, uint8_t y);
void draw_stat(uint8_t x, uint8_t y);
void draw_flightime(uint8_t x, uint8_t y);
void draw_climbeff(uint8_t x, uint8_t y);
void draw_eff(uint8_t x, uint8_t y);
void draw_atemp(uint8_t x, uint8_t y);
void draw_bat2_vlt(uint8_t x, uint8_t y);
void draw_bat2used(uint8_t x, uint8_t y);
void draw_clk(uint8_t x, uint8_t y);
void draw_callsign(uint8_t x, uint8_t y);
void draw_current2(uint8_t x, uint8_t y);
void draw_vtx_power(uint8_t x, uint8_t y);
void draw_hgt_abvterr(uint8_t x, uint8_t y);
#if AP_FENCE_ENABLED
void draw_fence(uint8_t x, uint8_t y);
#endif
#if AP_RANGEFINDER_ENABLED
void draw_rngf(uint8_t x, uint8_t y);
#endif
#if AP_OSD_EXTENDED_LNK_STATS
// Extended link stats data panels
bool is_btfl_fonts();
void draw_rc_tx_power(uint8_t x, uint8_t y);
void draw_rc_rssi_dbm(uint8_t x, uint8_t y);
void draw_rc_snr(uint8_t x, uint8_t y);
void draw_rc_active_antenna(uint8_t x, uint8_t y);
void draw_rc_lq(uint8_t x, uint8_t y);
#endif
struct {
bool load_attempted;
const char *str;
} callsign_data;
};
3.2 关键要点
绘制例程的实现。
void AP_OSD_Screen::draw(void)
├──> <!enabled || !backend>
│ └──> return;
├──> <HAL_OSD_SIDEBAR_ENABLE>
│ └──> DRAW_SETTING(sidebars);
│
├──> DRAW_SETTING(message);
├──> DRAW_SETTING(horizon);
├──> DRAW_SETTING(compass);
├──> DRAW_SETTING(altitude);
│
├──> <AP_TERRAIN_AVAILABLE>
│ └──> DRAW_SETTING(hgt_abvterr);
│
├──> <AP_RANGEFINDER_ENABLED>
│ └──> DRAW_SETTING(rngf);
│
├──> DRAW_SETTING(waypoint);
├──> DRAW_SETTING(xtrack_error);
├──> DRAW_SETTING(bat_volt);
├──> DRAW_SETTING(bat2_vlt);
├──> DRAW_SETTING(avgcellvolt);
├──> DRAW_SETTING(avgcellrestvolt);
├──> DRAW_SETTING(restvolt);
│
├──> <AP_RSSI_ENABLED>
│ ├──> DRAW_SETTING(rssi);
│ └──> DRAW_SETTING(link_quality);
│
├──> DRAW_SETTING(current);
├──> DRAW_SETTING(batused);
├──> DRAW_SETTING(bat2used);
├──> DRAW_SETTING(sats);
├──> DRAW_SETTING(fltmode);
├──> DRAW_SETTING(gspeed);
├──> DRAW_SETTING(aspeed);
├──> DRAW_SETTING(aspd1);
├──> DRAW_SETTING(aspd2);
├──> DRAW_SETTING(vspeed);
├──> DRAW_SETTING(throttle);
├──> DRAW_SETTING(heading);
├──> DRAW_SETTING(wind);
├──> DRAW_SETTING(home);
│
├──> <AP_RPM_ENABLED>
│ └──> DRAW_SETTING(rrpm);
│
├──> <AP_FENCE_ENABLED>
│ └──> DRAW_SETTING(fence);
│
├──> DRAW_SETTING(roll_angle);
├──> DRAW_SETTING(pitch_angle);
├──> DRAW_SETTING(temp);
│
├──> <BARO_MAX_INSTANCES > 1>
│ └──> DRAW_SETTING(btemp);
│
├──> DRAW_SETTING(atemp);
├──> DRAW_SETTING(hdop);
├──> DRAW_SETTING(flightime);
│
├──> <AP_RTC_ENABLED>
│ └──> DRAW_SETTING(clk);
│
├──> <AP_VIDEOTX_ENABLED>
│ └──> DRAW_SETTING(vtx_power);
│
├──> <HAL_WITH_ESC_TELEM>
│ ├──> DRAW_SETTING(esc_temp);
│ ├──> DRAW_SETTING(esc_rpm);
│ └──> DRAW_SETTING(esc_amps);
│
├──> DRAW_SETTING(gps_latitude);
├──> DRAW_SETTING(gps_longitude);
│
├──> <HAL_PLUSCODE_ENABLE>
│ └──> DRAW_SETTING(pluscode);
│
├──> DRAW_SETTING(dist);
├──> DRAW_SETTING(stat);
├──> DRAW_SETTING(climbeff);
├──> DRAW_SETTING(eff);
├──> DRAW_SETTING(callsign);
├──> DRAW_SETTING(current2);
│
└──> <AP_OSD_EXTENDED_LNK_STATS>
├──> DRAW_SETTING(rc_tx_power);
├──> DRAW_SETTING(rc_rssi_dbm);
├──> DRAW_SETTING(rc_snr);
├──> DRAW_SETTING(rc_active_antenna);
└──> DRAW_SETTING(rc_lq);
3.3 重要接口
3.3.1 基础接口
- void draw_altitude(uint8_t x, uint8_t y);
- void draw_bat_volt(uint8_t instance,VoltageType type,uint8_t x, uint8_t y);
- void draw_bat_volt(uint8_t x, uint8_t y);
- void draw_avgcellvolt(uint8_t x, uint8_t y);
- void draw_avgcellrestvolt(uint8_t x, uint8_t y);
- void draw_restvolt(uint8_t x, uint8_t y);
- void draw_rssi(uint8_t x, uint8_t y);
- void draw_link_quality(uint8_t x, uint8_t y);
- void draw_current(uint8_t x, uint8_t y);
- void draw_current(uint8_t instance, uint8_t x, uint8_t y);
- void draw_batused(uint8_t x, uint8_t y);
- void draw_batused(uint8_t instance, 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_message(uint8_t x, uint8_t y);
- void draw_gspeed(uint8_t x, uint8_t y);
- void draw_horizon(uint8_t x, uint8_t y);
- void draw_home(uint8_t x, uint8_t y);
- void draw_throttle(uint8_t x, uint8_t y);
- void draw_heading(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_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);
- void draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude);
- void draw_distance(uint8_t x, uint8_t y, float distance);
- char get_arrow_font_index (int32_t angle_cd);
- void draw_gps_latitude(uint8_t x, uint8_t y);
- void draw_gps_longitude(uint8_t x, uint8_t y);
- void draw_roll_angle(uint8_t x, uint8_t y);
- void draw_pitch_angle(uint8_t x, uint8_t y);
- void draw_temp(uint8_t x, uint8_t y);
- void draw_hdop(uint8_t x, uint8_t y);
- void draw_waypoint(uint8_t x, uint8_t y);
- void draw_xtrack_error(uint8_t x, uint8_t y);
- void draw_dist(uint8_t x, uint8_t y);
- void draw_stat(uint8_t x, uint8_t y);
- void draw_flightime(uint8_t x, uint8_t y);
- void draw_climbeff(uint8_t x, uint8_t y);
- void draw_eff(uint8_t x, uint8_t y);
- void draw_atemp(uint8_t x, uint8_t y);
- void draw_bat2_vlt(uint8_t x, uint8_t y);
- void draw_bat2used(uint8_t x, uint8_t y);
- void draw_clk(uint8_t x, uint8_t y);
- void draw_callsign(uint8_t x, uint8_t y);
- void draw_current2(uint8_t x, uint8_t y);
- void draw_vtx_power(uint8_t x, uint8_t y);
- void draw_hgt_abvterr(uint8_t x, uint8_t y);
展开一个接口,作为示例:
void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
{
float alt; // 定义变量 alt,用于存储相对高度值。
AP_AHRS &ahrs = AP::ahrs(); // 获取 ArduPilot 姿态和航向参考系统 (AHRS) 的引用。
WITH_SEMAPHORE(ahrs.get_semaphore());
// 确保在多线程环境下对 ahrs 数据的安全访问。
ahrs.get_relative_position_D_home(alt);
// 获取当前位置相对于 home (起飞点) 的垂直距离,单位为米,向下为正。
alt = -alt;
// 将下方向的距离取反,转换为向上的高度值。
backend->write(
x, y, false, // 在屏幕 (x, y) 坐标绘制,false 表示不启用特定显示属性。
"%4d%c", // 格式化字符串,4 位整数 + 单位符号字符。
(int)u_scale(ALTITUDE, alt), // 将高度值按当前单位体系换算(如米或英尺),并转换为整数。
u_icon(ALTITUDE) // 获取当前单位体系下的高度单位符号(如 'm' 或 'ft')。
);
}
3.3.2 RPM相关
注:当AP_RPM_ENABLED
使能。
- void draw_rrpm(uint8_t x, uint8_t y);
3.3.3 SideBar相关
注:当HAL_OSD_SIDEBAR_ENABLE
使能。
- void draw_sidebars(uint8_t x, uint8_t y);
3.3.4 PlusCode相关
注:当HAL_PLUSCODE_ENABLE
使能。
- void draw_pluscode(uint8_t x, uint8_t y);
3.3.5 ESC相关
注:当HAL_WITH_ESC_TELEM
使能。
- void draw_esc_temp(uint8_t x, uint8_t y);
- void draw_esc_rpm(uint8_t x, uint8_t y);
- void draw_esc_amps(uint8_t x, uint8_t y);
3.3.6 Baro相关
注:当BARO_MAX_INSTANCES > 1
使能。
- void draw_btemp(uint8_t x, uint8_t y);
3.3.7 围栏相关
注:当AP_FENCE_ENABLED
使能。
- void draw_fence(uint8_t x, uint8_t y);
3.3.8 测距相关
注:当AP_RANGEFINDER_ENABLED
使能。
- void draw_rngf(uint8_t x, uint8_t y);
3.3.9 ERSF相关(ELRS)
注:当AP_OSD_EXTENDED_LNK_STATS
使能。
- void draw_rc_tx_power(uint8_t x, uint8_t y);
- void draw_rc_rssi_dbm(uint8_t x, uint8_t y);
- void draw_rc_snr(uint8_t x, uint8_t y);
- void draw_rc_active_antenna(uint8_t x, uint8_t y);
- void draw_rc_lq(uint8_t x, uint8_t y);
4. 总结
总体来说,这里唯一需要注意的是x,y坐标不要越界。至于具体x,y范围,详见每个DO实例的配置情况。
5. 参考资料
【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计
【6】ArduPilot开源代码之AP_OSD