ArduPilot开源代码之AP_OSD_MAX7456
1. 源由
前面讨论了
本章将针对具体的AP_OSD_MAX7456类进行研讨。
2. 结构设计
2.1 成员变量
新增:
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
uint8_t video_signal_reg;
bool initialized;
uint8_t last_font;
int8_t last_v_offset;
int8_t last_h_offset;
static const uint8_t video_lines_ntsc = 13;
static const uint8_t video_lines_pal = 16;
static const uint8_t video_columns = 30;
static const uint16_t spi_buffer_size = 512;
uint8_t frame[video_lines_pal][video_columns];
//frame already transfered to max
//used to optimize number of characters updated
uint8_t shadow_frame[video_lines_pal][video_columns];
uint8_t buffer[spi_buffer_size];
int buffer_offset;
uint32_t last_signal_check;
uint32_t video_detect_time;
uint16_t video_lines;
2.2 OSD 符号
无自定义,将会保持与 AP_OSD_Backend 一致。
3. 接口设计
3.1 一次性接口
3.1.1 init
通过SPI对MAX7456进行重置,并更新字体库。
bool AP_OSD_MAX7456::init()
{
uint8_t status = 0xFF;
_dev->get_semaphore()->take_blocking();
_dev->write_register(MAX7456ADD_VM0, MAX7456_RESET);
hal.scheduler->delay(1);
_dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &status, 1);
_dev->get_semaphore()->give();
if (status != 0) {
return false;
}
return update_font();
}
3.1.2 osd_thread_run_once
无,使用 AP_OSD_Backend::osd_thread_run_once
3.1.3 init_symbol_set
无,使用 AP_OSD_Backend::init_symbol_set
3.1.4 probe
最初的初始化,直接在AP_OSD::init_backend中进行,详见:ArduPilot开源代码之AP_OSD
AP_OSD_Backend *AP_OSD_MAX7456::probe(AP_OSD &osd, AP_HAL::OwnPtr<AP_HAL::Device> dev)
{
if (!dev) {
return nullptr;
}
AP_OSD_MAX7456 *backend = NEW_NOTHROW AP_OSD_MAX7456(osd, std::move(dev));
if (!backend) {
return nullptr;
}
if (!backend->init()) {
delete backend;
return nullptr;
}
return backend;
}
3.2 基本操作
3.2.1 write
直接写入界面缓存中。
void AP_OSD_MAX7456::write(uint8_t x, uint8_t y, const char* text)
{
if (y >= video_lines_pal || text == nullptr) {
return;
}
while ((x < VIDEO_COLUMNS) && (*text != 0)) {
frame[y][x] = *text;
++text;
++x;
}
}
3.2.2 flush
通过SPI刷一帧数据到MAX7456
void AP_OSD_MAX7456::flush()
{
if (last_font != get_font_num()) {
update_font();
}
// check for offset changes
if (last_v_offset != _osd.v_offset) {
int8_t vos = constrain_int16(_osd.v_offset, 0, 31);
_dev->get_semaphore()->take_blocking();
_dev->write_register(MAX7456ADD_VOS, vos);
_dev->get_semaphore()->give();
last_v_offset = _osd.v_offset;
}
if (last_h_offset != _osd.h_offset) {
int8_t hos = constrain_int16(_osd.h_offset, 0, 63);
_dev->get_semaphore()->take_blocking();
_dev->write_register(MAX7456ADD_HOS, hos);
_dev->get_semaphore()->give();
last_h_offset = _osd.h_offset;
}
check_reinit();
transfer_frame();
}
3.2.3 clear
缓存清零,相当于OSD清空,但是MAX7456并不清空。
void AP_OSD_MAX7456::clear()
{
AP_OSD_Backend::clear();
memset(frame, ' ', sizeof(frame));
}
3.3 功能函数
3.3.1 is_compatible_with_backend_type
- 不兼容:OSD_MAX7456/OSD_SITL
- 兼容:OSD_MSP/OSD_MSP_DISPLAYPORT
bool is_compatible_with_backend_type(AP_OSD::osd_types type) const override {
switch(type) {
case AP_OSD::osd_types::OSD_MAX7456:
case AP_OSD::osd_types::OSD_SITL:
return false;
case AP_OSD::osd_types::OSD_NONE:
case AP_OSD::osd_types::OSD_TXONLY:
case AP_OSD::osd_types::OSD_MSP:
case AP_OSD::osd_types::OSD_MSP_DISPLAYPORT:
return true;
}
return false;
}
3.3.2 get_backend_type
AP_OSD::osd_types get_backend_type() const override {
return AP_OSD::osd_types::OSD_MAX7456;
}
3.3.3 get_aspect_ratio_correction
根据视频制式调整纵横比校正因子,确保屏幕显示(OSD)的角度和图形正确无误。解决像素宽高比导致的图形失真问题,确保OSD元素(如仪表、指针)按预期比例显示。
-
NTSC格式:
返回校正因子12.0f/18.46f ≈ 0.65。
NTSC的像素宽高比通常非正方形(如矩形像素),水平方向较宽。通过缩小水平长度或增加垂直长度,抵消像素拉伸,保持显示比例正确。 -
PAL格式:
返回校正因子12.0f/15.0f = 0.8。
PAL制式的像素宽高比差异较小,但仍需校正。因子0.8调整水平或垂直方向,确保图形比例准确。 -
默认情况:
返回1.0,即不进行校正(假设像素为正方形或无需调整)。
// return a correction factor used to display angles correctly
float AP_OSD_MAX7456::get_aspect_ratio_correction() const
{
switch (_format) {
case FORMAT_NTSC:
return 12.0f/18.46f;
case FORMAT_PAL:
return 12.0f/15.0f;
default:
return 1.0f;
};
}
4. 总结
AP_OSD_MAX7456类MAX7456芯片的对象(DO),通过SPI总线,将应用层在AP_OSD`处理结果发送给芯片。
5. 参考资料
【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计
【6】ArduPilot开源代码之AP_OSD_Backend
1000

被折叠的 条评论
为什么被折叠?



