PX4模块设计之二十八:RCInput模块
Posted lida2003
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了PX4模块设计之二十八:RCInput模块相关的知识,希望对你有一定的参考价值。
PX4模块设计之二十八:RCInput模块
1. RCInput模块简介
RC遥控支持如下协议:
- PPM
- SBUS
- DSM
- SUMD
- ST24
- CRSF
- GHST
### Description
This module does the RC input parsing and auto-selecting the method. Supported methods are:
- PPM
- SBUS
- DSM
- SUMD
- ST24
- TBS Crossfire (CRSF)
rc_input <command> [arguments...]
Commands:
start
[-d <val>] /dev/ttyS3 "RC device"
bind Send a DSM bind command (module must be running)
stop
status print status info
注:print_usage函数是具体对应实现。
class RCInput : public ModuleBase<RCInput>, public ModuleParams, public px4::ScheduledWorkItem
注:RCInput模块采用了ModuleBase和WorkQueue设计。
2. 模块入口函数
2.1 主入口rc_input_main
同样继承了ModuleBase,由ModuleBase的main来完成模块入口。
rc_input_main
└──> return RCInput::main(argc, argv)
2.2 自定义子命令custom_command
除start/stop/status命令,自定义命令支持bind,主要用于接收机与发射机的绑定。
RCInput::custom_command
├──> <SPEKTRUM_POWER><!strcmp(verb, "bind")>
│ ├──> uORB::Publication<vehicle_command_s> vehicle_command_pubORB_ID(vehicle_command)
│ ├──> vehicle_command_s vcmd
│ ├──> vcmd.command = vehicle_command_s::VEHICLE_CMD_START_RX_PAIR
│ ├──> vcmd.timestamp = hrt_absolute_time()
│ ├──> vehicle_command_pub.publish(vcmd)
│ └──> return 0
├──> <!is_running()>
│ ├──> int ret = RCInput::task_spawn(argc, argv)
│ └──> <ret>
│ └──> return ret
└──> return print_usage("unknown command")
2.3 模块状态print_status【重载】
这里重载了ModuleBase的print_status方法,将RCInput相关的状态信息进行输出。
RCInput::print_status
├──> PX4_INFO("Max update rate: %u Hz", 1000000 / _current_update_interval)
├──> <_device[0] != '\\0'>
│ ├──> PX4_INFO("UART device: %s", _device)
│ └──> PX4_INFO("UART RX bytes: %" PRIu32, _bytes_rx)
├──> PX4_INFO("RC state: %s: %s", _rc_scan_locked ? "found" : "searching for signal", RC_SCAN_STRING[_rc_scan_state])
├──> <_rc_scan_locked>
│ ├──> <RC_SCAN_CRSF>
│ │ └──> PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no")
│ ├──> <RC_SCAN_GHST>
│ │ └──> PX4_INFO("GHST Telemetry: %s", _ghst_telemetry ? "yes" : "no")
│ ├──> <RC_SCAN_SBUS>
│ │ └──> PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames())
│ └──> <other RC Protocol>
│ └──> [No Prints]
├──> <_analog_rc_rssi_stable>
│ └──> PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f))
├──> perf_print_counter(_cycle_perf)
├──> perf_print_counter(_publish_interval_perf)
├──> <hrt_elapsed_time(&_rc_in.timestamp) < 1_s>
│ └──> print_message(ORB_ID(input_rc), _rc_in)
└──> return 0
3. RCInput模块重要函数
3.1 task_spawn
RCInput::task_spawn
├──> [解析RC通信设备,默认:RC_SERIAL_PORT] // KakuteF7 --> "/dev/ttyS4"
├──> <!device_name && (access(device_name, R_OK | W_OK) == 0)>
│ └──> return PX4_ERROR // device error
├──> RCInput *instance = new RCInput(device_name)
├──> <instance == nullptr>
│ ├──> PX4_ERR("alloc failed")
│ └──> return PX4_ERROR
├──> _object.store(instance)
├──> _task_id = task_id_is_work_queue
├──> instance->ScheduleOnInterval(_current_update_interval) //250Hz
└──> return PX4_OK
3.2 instantiate
注:鉴于该模块不采用任务(线程),所以ModuleBase::run_trampoline无需执行,所以可以不实现。
3.3 init
注:鉴于涉及底层实现,从模块业务角度不再展开,后续有时间我们在深入讨论。
3.4 Run
RCInput::Run
├──> [优雅退出处理]
├──> [RC设备通信初始化]
├──> <_parameter_update_sub.updated()>
│ ├──> parameter_update_s param_update;
│ ├──> _parameter_update_sub.copy(¶m_update);
│ └──> updateParams();
├──> <_vehicle_status_sub.updated()><_vehicle_status_sub.copy(&vehicle_status)>
│ └──> _armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED)
├──> <_vehicle_cmd_sub.update(&vcmd)><vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR>
│ ├──> uint8_t cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_UNSUPPORTED
│ ├──> <SPEKTRUM_POWER>
│ │ └──> [DSM bind RxTx]
│ ├──> vehicle_command_ack_s command_ack;
│ ├──> command_ack.command = vcmd.command;
│ ├──> command_ack.result = cmd_ret;
│ ├──> command_ack.target_system = vcmd.source_system;
│ ├──> command_ack.target_component = vcmd.source_component;
│ ├──> command_ack.timestamp = hrt_absolute_time();
│ ├──> uORB::Publication<vehicle_command_ack_s> vehicle_command_ack_pubORB_ID(vehicle_command_ack);
│ └──> vehicle_command_ack_pub.publish(command_ack);
├──> <ADC_RC_RSSI_CHANNEL>
│ └──> [ADC RSSI 信号强度及状态更新]
├──> [500ms进行RC协议扫描,支持SBUS/DSM/ST24/SUMD/PPM/CRSF/GHST]
├──> [发布ORB_ID(input_rc)消息]
└──> [超过3秒成功锁定协议,设置RC_INPUT_PROTO]
4. 总结
后续针对RC通信方面可以继续深入单总线串行口底层实现以及各协议格式的深入研究,入口如下:
- PPM解析函数 --> hrt_ppm_decode
- SBUS解析函数 --> sbus_parse
- DSM解析函数 --> dsm_parse
- SUMD解析函数 --> sumd_decode
- ST24解析函数 --> st24_decode
- CRSF解析函数 --> crsf_parse
- GHST解析函数 --> ghst_parse
- 单总线串口底层初始化 --> RCInput::init
5. 参考资料
【1】PX4开源软件框架简明简介
【2】PX4模块设计之十一:Built-In框架
【3】PX4模块设计之十二:High Resolution Timer设计
【4】PX4模块设计之十三:WorkQueue设计
【5】PX4模块设计之十七:ModuleBase模块
【6】PX4 modules_main
【7】RC Protocols Explained: SBUS, CRSF, PWM, FPort and More
以上是关于PX4模块设计之二十八:RCInput模块的主要内容,如果未能解决你的问题,请参考以下文章