• PX4模块设计之二十六:BatteryStatus模块


    1. BatteryStatus模块简介

    ### Description
    
    The provided functionality includes:
    - Read the output from the ADC driver (via ioctl interface) and publish `battery_status`.
    
    
    ### Implementation
    It runs in its own thread and polls on the currently selected gyro topic.
    
    battery_status  [arguments...]
     Commands:
       start
    
       stop
    
       status        print status info
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16

    注:print_usage函数是具体对应实现。

    class BatteryStatus : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem
    
    • 1

    注:battery_status模块采用了ModuleBaseWorkQueue设计。

    2. 模块入口函数

    2.1 主入口battery_status_main

    这里比较简单,继承了ModuleBase,由ModuleBase的main来完成模块入口。

    battery_status_main
     └──> return BatteryStatus::main(argc, argv)
    
    • 1
    • 2

    2.2 自定义子命令custom_command

    模块仅支持start/stop/status命令,不支持其他自定义命令。

    BatteryStatus::custom_command
     └──> return print_usage("unknown command")
    
    • 1
    • 2

    3. BatteryStatus模块重要函数

    3.1 task_spawn

    这里主要初始化了BatteryStatus对象,后续通过WorkQueue来完成进行轮询

    BatteryStatus::task_spawn
     ├──> BatteryStatus *instance = new BatteryStatus()
     ├──> 
     │   ├──> _object.store(instance)
     │   ├──> _task_id = task_id_is_work_queue
     │   └──> init()>
     │       └──> return PX4_OK
     ├──> 
     │   └──> PX4_ERR("alloc failed")
     ├──> delete instance
     ├──> _object.store(nullptr)
     ├──> _task_id = -1
     └──> return PX4_ERROR
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13

    3.2 instantiate

    注:鉴于该模块不采用任务(线程),所以ModuleBase::run_trampoline无需执行,所以可以不实现。

    3.3 init

    在task_spawn中使用,对_adc_report_sub成员变量进行事件回调注册(当有adc_report消息时,会调用SubscriptionCallbackWorkItem::ScheduleNow,再触发BatteryStatus::Run过程)。

    BatteryStatus::init
     └──> return _adc_report_sub.registerCallback()
    
    • 1
    • 2

    注:这里真正调用ScheduleNow的不是BatteryStatus类,而是该类内部成员变量_adc_report_sub。

    uORB::SubscriptionCallbackWorkItem _adc_report_sub{this, ORB_ID(adc_report)};
    
    • 1

    3.4 Run

    每次WorkQueue执行,会自动调用Run函数,详见:PX4模块设计之十三:WorkQueue设计

    BatteryStatus::Run
     ├──> 
     │   ├──> exit_and_cleanup()
     │   └──> return
     ├──> perf_begin(_loop_perf)
     ├──> parameter_update_poll()  // check parameters for updates
     ├──> adc_poll()  // check battery voltage
     └──> perf_end(_loop_perf)
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8

    注:关于adc_report消息的来由,可参考:PX4模块设计之二十四:内部ADC模块

    4. 硬件配置

    鉴于当前硬件板子使用的是Holybro Kakute AIO F7,其硬件配置如下:

    86 #define ADC_RSSI_IN_CHANNEL                 /* PC5 */  ADC1_CH(15)
    87 #define ADC_BATTERY_VOLTAGE_CHANNEL         /* PC3 */  ADC1_CH(13)
    88 #define ADC_BATTERY_CURRENT_CHANNEL         /* PC2 */  ADC1_CH(12)
    89 
    90 #define ADC_CHANNELS \
    91 	((1 << ADC_BATTERY_VOLTAGE_CHANNEL)       | \
    92 	 (1 << ADC_BATTERY_CURRENT_CHANNEL)       | \
    93 	 (1 << ADC_RSSI_IN_CHANNEL))
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    138 #if !defined(BOARD_NUMBER_BRICKS)
    139 #  define BOARD_NUMBER_BRICKS 1
    140 #  if !defined(BOARD_ADC_BRICK_VALID)
    141 #    define BOARD_ADC_BRICK_VALID (1)
    142 #  endif
    143 #endif
    144
    145 #if BOARD_NUMBER_BRICKS == 0
    146 /* allow SITL to disable all bricks */
    147 #elif BOARD_NUMBER_BRICKS == 1
    148 #  define BOARD_BATT_V_LIST       {ADC_BATTERY_VOLTAGE_CHANNEL}
    149 #  define BOARD_BATT_I_LIST       {ADC_BATTERY_CURRENT_CHANNEL}
    150 #  define BOARD_BRICK_VALID_LIST  {BOARD_ADC_BRICK_VALID}
    151 #elif BOARD_NUMBER_BRICKS == 2
    152 #  if  defined(BOARD_NUMBER_DIGITAL_BRICKS)
    153 #    define BOARD_BATT_V_LIST       {-1, -1}
    154 #    define BOARD_BATT_I_LIST       {-1, -1}
    155 #  else
    156 #    define BOARD_BATT_V_LIST       {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL}
    157 #    define BOARD_BATT_I_LIST       {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL}
    158 #  endif
    159 #  define BOARD_BRICK_VALID_LIST  {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID}
    160 #elif BOARD_NUMBER_BRICKS == 3
    161 #  define BOARD_BATT_V_LIST       {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL}
    162 #  define BOARD_BATT_I_LIST       {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL}
    163 #  define BOARD_BRICK_VALID_LIST  {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID}
    164 #elif BOARD_NUMBER_BRICKS == 4
    165 #  define BOARD_BATT_V_LIST       {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL, ADC_BATTERY4_VOLTAGE_CHANNEL}
    166 #  define BOARD_BATT_I_LIST       {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL, ADC_BATTERY4_CURRENT_CHANNEL}
    167 #  define BOARD_BRICK_VALID_LIST  {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID, BOARD_ADC_BRICK4_VALID}
    168 #else
    169 #  error Unsuported BOARD_NUMBER_BRICKS number.
    170 #endif
    171 
    172 /* Choose the source for ADC_SCALED_V5_SENSE */
    173 #if defined(ADC_5V_RAIL_SENSE)
    174 #define ADC_SCALED_V5_SENSE ADC_5V_RAIL_SENSE
    175 #else
    176 #  if defined(ADC_SCALED_V5_CHANNEL)
    177 #    define ADC_SCALED_V5_SENSE ADC_SCALED_V5_CHANNEL
    178 #  endif
    179 #endif
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16
    • 17
    • 18
    • 19
    • 20
    • 21
    • 22
    • 23
    • 24
    • 25
    • 26
    • 27
    • 28
    • 29
    • 30
    • 31
    • 32
    • 33
    • 34
    • 35
    • 36
    • 37
    • 38
    • 39
    • 40
    • 41
    • 42

    5. 总结

    模块有对adc数据进行过滤但是命令行没有相应的输出显示,也没有将处理后的adc数据发送到系统中。可能这仅仅如代码中写的,是遗产吧。

    platforms/common/include/px4_platform_common/board_common.h

    136 /* Legacy default */
    
    • 1

    6. 参考资料

    【1】PX4开源软件框架简明简介
    【2】PX4模块设计之十一:Built-In框架
    【3】PX4模块设计之十二:High Resolution Timer设计
    【4】PX4模块设计之十三:WorkQueue设计
    【5】PX4模块设计之十七:ModuleBase模块
    【6】PX4 modules_main
    【7】PX4模块设计之二十四:内部ADC模块

  • 相关阅读:
    scale自适应分辨率 实现缩放自适应(vue3)
    MarkText如何实现图床-解决md上传到csdn图片不显示的问题
    【深度学习】《机器学习硕博生建议掌握的九个工具》学习笔记
    【Linux】shell命令以及运行原理和Linux权限详解
    LeetCode99之恢复二叉搜索树(相关话题:中序遍历)
    什么是坚韧型人格?坚韧型人格的职业发展规划
    贪心算法
    贝叶斯优化核极限学习机KELM用于回归预测
    Lua 支持虚函数的解决方案
    异步编程真的让程序更快了吗?
  • 原文地址:https://blog.csdn.net/lida2003/article/details/126581755