PX4模块设计之四十二:ATXXXX模块
Posted lida2003
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之四十二:ATXXXX模块相关的知识,希望对你有一定的参考价值。
PX4模块设计之四十二:ATXXXX模块
1. ATXXXX模块简介
### Description
OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example.
It can be enabled with the OSD_ATXXXX_CFG parameter.
atxxxx <command> [arguments...]
Commands:
start
[-s] Internal SPI bus(es)
[-S] External SPI bus(es)
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
(default=1))
[-c <val>] chip-select pin (for internal SPI) or index (for external SPI)
[-m <val>] SPI mode
[-f <val>] bus frequency in kHz
[-q] quiet startup (no message if no device found)
stop
status print status info
注1:print_usage函数是具体对应实现。
class OSDatxxxx : public device::SPI, public ModuleParams, public I2CSPIDriver<OSDatxxxx>
class I2CSPIDriver : public I2CSPIDriverBase
class I2CSPIDriverBase : public px4::ScheduledWorkItem, public I2CSPIInstance
class ScheduledWorkItem : public WorkItem
class WorkItem : public IntrusiveSortedListNode<WorkItem *>, public IntrusiveQueueNode<WorkItem *>
class I2CSPIInstance : public ListNode<I2CSPIInstance *>
class ModuleParams : public ListNode<ModuleParams *>
OSDatxxxx //类继承关系
├──> I2CSPIDriver
│ └──> I2CSPIDriverBase
│ ├──> px4::ScheduledWorkItem
│ │ └──> WorkItem
│ │ ├──> IntrusiveSortedListNode
│ │ └──> IntrusiveQueueNode
│ └──> I2CSPIInstance
│ └──> ListNode
├──> device::SPI
└──> ModuleParams
└──> ListNode
注2:ATXXXX模块继承了OSDatxxxx类的所有方法,其主体实现详见OSDatxxxx类。
2. 模块入口函数
2.1 主入口atxxxx_main
模块支持start/stop/status命令,除此以外支持BusCLIArguments的I2C/SPI默认参数选项"XIa:SscⓂ️kb:f:q"。
atxxxx_main
├──> using ThisDriver = OSDatxxxx
├──> BusCLIArguments clifalse, true //默认SPI总线
├──> cli.spi_mode = SPIDEV_MODE0
├──> cli.default_spi_frequency = OSD_SPI_BUS_SPEED //默认2M SPI总线频率
├──> const char *verb = cli.parseDefaultArguments(argc, argv) // 默认解析"XIa:Ssc:m:kb:f:q"选项参数
├──> <!verb>
│ ├──> ThisDriver::print_usage()
│ └──> return -1
├──> BusInstanceIterator iterator(MODULE_NAME, cli, DRV_OSD_DEVTYPE_ATXXXX)
├──> <!strcmp(verb, "start")>
│ └──>return ThisDriver::module_start(cli, iterator) //模块启动
├──> <!strcmp(verb, "stop")>
│ └──>return ThisDriver::module_stop(iterator) //模块停止
├──> <!strcmp(verb, "status")>
│ └──>return ThisDriver::module_status(iterator) //模块状态
├──> ThisDriver::print_usage()
└──> return -1
2.2 自定义子命令custom_command
注:该模块采用了纯C语言代码实现,在main函数中直接执行命令,无需ModuleBase的custom_command重载实现。
2.3 模块状态print_status【重载】
该模块采用了纯C语言代码实现,在main函数中直接执行ThisDriver::print_usage()函数,无需ModuleBase的模块状态print_status重载实现。
void
OSDatxxxx::print_usage()
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
OSD driver for the ATXXXX chip that is mounted on the OmnibusF4SD board for example.
It can be enabled with the OSD_ATXXXX_CFG parameter.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("atxxxx", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
3. ATXXXX模块重要函数
3.1 模块启动ThisDriver::module_start
启动过程会将以下驱动信息关联到设备实例上:
- static I2CSPIDriverBase *I2CSPIDriver::instantiate_default(const I2CSPIDriverConfig &config, int runtime_instance)
- int OSDatxxxx::init()
- void OSDatxxxx::RunImpl()
- void I2CSPIDriver::Run() final
ThisDriver::module_start(OSDatxxxx::module_start)
└──> I2CSPIDriver::module_start
└──> I2CSPIDriverBase::module_start
注:I2CSPIDriverBase::module_start会进行第一次的Run激活(px4::WorkItemSingleShot)。
3.2 模块停止ThisDriver::module_stop
ThisDriver::module_stop(OSDatxxxx::module_stop)
└──> I2CSPIDriverBase::module_stop
注:I2CSPIDriverBase类的通用方法,不在这里展开。
3.3 模块状态ThisDriver::module_status
ThisDriver::module_status(OSDatxxxx::module_status)
└──> I2CSPIDriverBase::module_status
注:I2CSPIDriverBase类的通用方法,不在这里展开。
3.4 设备实例对象初始化I2CSPIDriver::instantiate_default
该方法在I2CSPIDriverBase::module_start函数里面调用,其目的是新建一个设备对象实例,并进行初始化。
I2CSPIDriver::instantiate_default
├──> instance = new T(config) // 新建一个OSDatxxxx设备对象实例
├──> <!instance>
│ ├──> PX4_ERR("alloc failed")
│ └──> return nullptr
├──> <OK != instance->init()> // OSDatxxxx设备对象实例初始化
│ ├──> delete instance
│ └──> return nullptr
└──> return instance
3.5 OSDatxxxx设备实例对象初始化OSDatxxxx::init
OSDatxxxx设备初始化
OSDatxxxx::init
├──> int ret = SPI::init() //do SPI init (and probe) first
├──> <ret != PX4_OK>
│ └──> return ret
├──> ret = reset()
├──> <ret != PX4_OK>
│ └──> return ret
├──> ret = init_osd()
├──> <ret != PX4_OK>
│ └──> return ret
├──> [clear the screen]
│ ├──> int num_rows = (_param_osd_atxxxx_cfg.get() == 1 ? OSD_NUM_ROWS_NTSC : OSD_NUM_ROWS_PAL) //
│ └──> for (int i = 0 i < OSD_CHARS_PER_ROW i++)
│ └──> for (int j = 0 j < num_rows j++)
│ └──> add_character_to_screen(' ', i, j)
├──> start() // 挂在Work到队列, ScheduleOnInterval(OSD_UPDATE_RATE, 10000);
└──> return PX4_OK
3.6 设备实例对象任务I2CSPIDriver::Run()
OSDatxxxx设备初始化时以及设置定时时间,定时轮询Run过程,并调用业务实现方法RunImpl。
I2CSPIDriver::Run
├──> static_cast<T *>(this)->RunImpl()
└──> <should_exit()>
└──> exit_and_cleanup() //优雅退出处理
3.7 OSDatxxxx设备实例对象任务OSDatxxxx::RunImpl
根据订阅消息变化,更新OSD内容(buffer)
OSDatxxxx::RunImpl
├──> <should_exit()>
│ ├──> exit_and_cleanup(); //优雅退出处理
│ └──> return;
├──> update_topics();
└──> update_screen();
4. 总结
具体逻辑业务后续再做深入,从模块代码角度:
- 输入
uORB::Subscription _battery_subORB_ID(battery_status);
uORB::Subscription _local_position_subORB_ID(vehicle_local_position);
uORB::Subscription _vehicle_status_subORB_ID(vehicle_status);
- 输出: 修改OSD显示内容
5. 参考资料
【1】PX4开源软件框架简明简介
【2】PX4模块设计之十一:Built-In框架
【3】PX4模块设计之十二:High Resolution Timer设计
【4】PX4模块设计之十三:WorkQueue设计
【5】PX4模块设计之十七:ModuleBase模块
【6】PX4模块设计之三十:Hysteresis类
【7】PX4 modules_main
【8】PX4模块设计之四十一:I2C/SPI Bus Instance基础知识
以上是关于PX4模块设计之四十二:ATXXXX模块的主要内容,如果未能解决你的问题,请参考以下文章