PX4模块设计之三十三:Sensors模块

Sensors模块在PX4中扮演关键角色,整合来自不同传感器的低级数据,进行投票、故障处理、校准,并发布到系统。它监控传感器驱动的输出,更新校准参数,执行一致性检查,并发布状态信息。模块支持start、stop和status命令,使用WorkQueue进行轮询。初始化时注册传感器回调,不断检查新传感器并发布sensor_combined、airspeed和differential_pressure等消息。

1. Sensors模块简介

Sensors模块汇总了所有的飞控传感器,最终将处理后的传感数据以sensor_combined/airspeed/differential_pressure消息发布到系统中。

### Description
The sensors module is central to the whole system. It takes low-level output from drivers, turns
it into a more usable form, and publishes it for the rest of the system.

The provided functionality includes:
- Read the output from the sensor drivers (`sensor_gyro`, etc.).
  If there are multiple of the same type, do voting and failover handling.
  Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the
  topics is `sensor_combined`, used by many parts of the system.
- Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or
  on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the
  sensor drivers must already be running when `sensors` is started.
- Do sensor consistency checks and publish the `sensors_status_imu` topic.

### Implementation
It runs in its own thread and polls on the currently selected gyro topic.

sensors <command> [arguments...]
 Commands:
   start
     [-h]        Start in HIL mode

   stop

   status        print status info

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

class Sensors : public ModuleBase<Sensors>, public ModuleParams, public px4::ScheduledWorkItemModuleParams, public px4::WorkItem

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

2. 模块入口函数

2.1 主入口sensors_main

同样继承了ModuleBase,由ModuleBase的main来完成模块入口。

sensors_main
 └──> return Sensors::main(argc, argv)

2.2 自定义子命令custom_command

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

Sensors::custom_command
 └──> return print_usage("unknown command");

2.3 模块状态print_status【重载】

Sensors::print_status
 ├──> _voted_sensors_update.printStatus();
 ├──> <CONFIG_SENSORS_VEHICLE_MAGNETOMETER><_vehicle_magnetometer>
 │   ├──> PX4_INFO_RAW("\n");
 │   └──> _vehicle_magnetometer->PrintStatus();
 ├──> <CONFIG_SENSORS_VEHICLE_AIR_DATA><_vehicle_air_data>
 │   ├──> PX4_INFO_RAW("\n");
 │   └──> _vehicle_air_data->PrintStatus();
 ├──> <CONFIG_SENSORS_VEHICLE_AIRSPEED>
 │   ├──> PX4_INFO_RAW("\n");
 │   ├──> PX4_INFO_RAW("Airspeed status:\n");
 │   └──> _airspeed_validator.print();
 ├──> <CONFIG_SENSORS_VEHICLE_OPTICAL_FLOW><_vehicle_optical_flow>
 │   ├──> PX4_INFO_RAW("\n");
 │   └──> _vehicle_optical_flow->PrintStatus();
 ├──> <CONFIG_SENSORS_VEHICLE_GPS_POSITION><_vehicle_gps_position>
 │   ├──> PX4_INFO_RAW("\n");
 │   └──> _vehicle_gps_position->PrintStatus();
 ├──> PX4_INFO_RAW("\n");
 ├──> _vehicle_acceleration.PrintStatus();
 ├──> PX4_INFO_RAW("\n");
 ├──> _vehicle_angular_velocity.PrintStatus();
 ├──> PX4_INFO_RAW("\n");
 ├──> <for (auto &i : _vehicle_imu_list)><i != nullptr>
 │   ├──> PX4_INFO_RAW("\n");
 │   └──> i->PrintStatus();
 └──> return 0;

3. Sensors模块重要函数

3.1 task_spawn

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

Sensors::task_spawn
 ├──> bool hil_enabled = false
 ├──> [命令行输入参数,解析hil_enabled]
 ├──> Sensors *instance = new Sensors(hil_enabled)
 ├──> <instance>
 │   ├──> _object.store(instance)
 │   ├──> _task_id = task_id_is_work_queue
 │   └──> <instance->init()>
 │       └──> return PX4_OK
 ├──> <else>
 │   └──> PX4_ERR("alloc failed")
 ├──> delete instance
 ├──> _object.store(nullptr)
 ├──> _task_id = -1
 └──> return PX4_ERROR

3.2 instantiate

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

3.3 init

在task_spawn中调用init进行ScheduleNow初次调用,后续对_vehicle_imu_sub成员变量进行事件回调注册(当有Sensors消息时,会调用SubscriptionCallbackWorkItem::ScheduleNow,再触发Sensors::Run过程)。

Sensors::init
 ├──> _vehicle_imu_sub[0].registerCallback()  // 这里有点奇怪,为什么只是注册一个IMU;假如多个IMU,第0个损坏且数据不发生变化,怎么办???
 ├──> ScheduleNow()
 └──> return true

注:最多支持4个IMU设备。

uORB::SubscriptionCallbackWorkItem _vehicle_imu_sub[MAX_SENSOR_COUNT] {
	{this, ORB_ID(vehicle_imu), 0},
	{this, ORB_ID(vehicle_imu), 1},
	{this, ORB_ID(vehicle_imu), 2},
	{this, ORB_ID(vehicle_imu), 3}
};

3.4 Run

在没有解锁时进行传感器遍历和添加;当解锁以后就不在添加传感器,仅对当前已经确认支持的传感设备进行数据更新。

Sensors::Run
 ├──> [优雅退出处理]
 ├──> <_vcontrol_mode_sub.updated()><_vcontrol_mode_sub.copy(&vcontrol_mode)>
 │   └──> _armed = vcontrol_mode.flag_armed
 ├──> <(!_armed && hrt_elapsed_time(&_last_config_update) > 500_ms) || (_last_config_update == 0)>   // keep adding sensors as long as we are not armed
 │   ├──> bool updated = false
 │   ├──> <CONFIG_SENSORS_VEHICLE_AIR_DATA>
 │   │   ├──> const int n_baro = orb_group_count(ORB_ID(sensor_baro))
 │   │   └──> <n_baro != _n_baro>
 │   │       └──> _n_baro = n_baro; updated = true;
 │   ├──> <CONFIG_SENSORS_VEHICLE_GPS_POSITION>
 │   │   ├──> const int n_gps = orb_group_count(ORB_ID(sensor_gps))
 │   │   └──> <n_gps != _n_gps>
 │   │       └──> _n_gps = n_gps; updated = true;
 │   ├──> <CONFIG_SENSORS_VEHICLE_MAGNETOMETER>
 │   │   ├──> const int n_mag = orb_group_count(ORB_ID(sensor_mag))
 │   │   └──> <n_mag != _n_mag>
 │   │       └──> _n_mag = n_mag; updated = true;
 │   ├──> <CONFIG_SENSORS_VEHICLE_OPTICAL_FLOW>
 │   │   ├──> const int n_optical_flow = orb_group_count(ORB_ID(sensor_optical_flow))
 │   │   └──> <n_optical_flow != _n_optical_flow>
 │   │       └──> _n_optical_flow = n_optical_flow; updated = true;
 │   ├──> const int n_accel = orb_group_count(ORB_ID(sensor_accel));
 │   ├──> const int n_gyro  = orb_group_count(ORB_ID(sensor_gyro));
 │   ├──> <(n_accel != _n_accel) || (n_gyro != _n_gyro) || updated>
 │   │   ├──> _n_accel = n_accel;
 │   │   ├──> _n_gyro = n_gyro;
 │   │   └──> parameters_update();
 │   ├──> _voted_sensors_update.initializeSensors();
 │   ├──> InitializeVehicleIMU();
 │   └──> _last_config_update = hrt_absolute_time();
 ├──> <else><_parameter_update_sub.updated()>  // when not adding sensors poll for param updates
 │   ├──> _parameter_update_sub.copy(&pupdate);
 │   ├──> parameters_update();
 │   └──> updateParams();
 ├──> _voted_sensors_update.sensorsPoll(_sensor_combined);
 ├──> <_sensor_combined.timestamp != _sensor_combined_prev_timestamp>
 │   ├──> _voted_sensors_update.setRelativeTimestamps(_sensor_combined);
 │   ├──> _sensor_pub.publish(_sensor_combined);                                 // 发布sensor_combined消息
 │   └──> _sensor_combined_prev_timestamp = _sensor_combined.timestamp;
 ├──> <CONFIG_SENSORS_VEHICLE_AIRSPEED>   // check analog airspeed
 │   ├──> adc_poll();      //发布differential_pressure消息
 │   └──> diff_pres_poll();      //发布airspeed消息
 └──> ScheduleDelayed(10_ms);  // backup schedule as a watchdog timeout

4. 总结

该模块主要处理多IMU数据,空速计,气压差传感数据,从代码角度:

  • 输入
uORB::SubscriptionCallbackWorkItem _vehicle_imu_sub[MAX_SENSOR_COUNT] {{this, ORB_ID(vehicle_imu), 0},{this, ORB_ID(vehicle_imu), 1},{this, ORB_ID(vehicle_imu), 2},{this, ORB_ID(vehicle_imu), 3}};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)};
uORB::Subscription _diff_pres_sub {ORB_ID(differential_pressure)};
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};
uORB::Subscription _adc_report_sub {ORB_ID(adc_report)};
  • 输出
uORB::Publication<sensor_combined_s>      _sensor_pub{ORB_ID(sensor_combined)};
uORB::Publication<airspeed_s>             _airspeed_pub{ORB_ID(airspeed)};
uORB::PublicationMulti<differential_pressure_s> _diff_pres_pub{ORB_ID(differential_pressure)};

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

<think>好的,用户现在想了解PX4飞控系统的供电方式以及如何为各个模块提供电源支持。我需要先回顾之前的对话,看看有没有相关的信息已经提到过。在之前的回答中,用户问过PX4飞控接口的连接方法,其中提到了电源接口,包括VBAT/GND和5V供电,还有安全注意事项里的电源模块校准。现在用户更深入地询问各模块的供电方式和电源设计,需要详细展开。 首先,用户提到的引用里,引用[1]和[4]提到了PX4的硬件结构,比如PIXHAWK整合了PX4FMU和PX4IO,以及OLDX-FC开源飞控的供电模块接口。这些信息可以帮助解释PX4的电源设计。引用[3]提到PX4可以运行在不同硬件上,需要考虑物理尺寸和成本,这也可能影响供电方案的选择。 用户的需求是了解整个PX4系统的供电方式,包括飞控本身和外接模块的电源支持。我需要分模块来回答,比如飞控核心、传感器、执行机构等,每个部分的电压要求、连接方式以及注意事项。 在之前的回答中,已经提到了VBAT和5V供电接口,现在需要更详细地说明这些接口的应用场景,比如VBAT直接接电池,5V由电源模块转换而来。同时,可能需要提到电源模块的参数设置,比如BAT_V_DIV和BAT_V_CHANNEL,这些校准步骤对于正确供电很重要。 另外,用户可能关心如何为外设如GPS、数传、摄像头等供电。需要根据引用中的信息,比如引用[4]中的接口说明,指出不同模块的电压需求,比如GPS通常是5V,光流可能用3.3V,执行机构如电调直接由电池供电。还要注意防反接和过流保护,避免损坏设备。 此外,用户可能遇到的实际问题,比如电源干扰或电压不足,需要给出排查步骤,比如测量电压、检查线路等。同时,安全注意事项也很重要,比如校准电源模块和避免同时使用多个供电来源。 需要确保回答结构清晰,分点说明,包括核心供电设计、外设供电方案、安全设计、故障排查等。可能还需要比较不同供电方案的优缺点,比如UBEC和电池直连的选择,这在用户之前的问题中也提到过相关问题,可以适当引用之前的回答内容。 最后,生成的相关问题需要与供电相关,比如不同模块的电源设计差异,电源干扰处理,多电池系统设计等,帮助用户进一步了解。</think>以下关于PX4飞控系统供电设计的解析基于官方文档与典型应用场景整理[^1][^3][^4]: --- ### 一、PX4供电架构设计原理 PX4采用**分布式电源管理系统**,核心设计理念为: $$ V_{sys} = \begin{cases} VBAT & \text{(主电源直连)} \\ 5V/3.3V & \text{(稳压输出)} \end{cases} $$ 通过PMIC(电源管理芯片)实现多级电压转换[^4] #### 1. 核心模块供电 | 模块名称 | 供电方式 | 电压范围 | 典型电流 | |----------------|-------------------------|------------|----------| | FMU处理器 | 5V稳压供电 | 4.75-5.25V | 350mA | | 传感器组 | 3.3V LDO输出 | 3.0-3.6V | 200mA | | 安全协处理器 | 独立3.3V供电 | 3.3V±5% | 50mA | | 接口板(PX4IO) | VBAT直连(需隔离电路) | 7-36V | 1A | --- ### 二、典型供电接口配置 #### 1. 主电源输入 - **VBAT/GND**:直接连接动力电池(2S-6S LiPo) - 推荐线径:18AWG(持续电流>30A) - 必须配置反接保护二极管: $$ P_{diode} = I_{max} \times V_f \times 1.5 $$ 例:SS34肖特基二极管(3A/40V) #### 2. 外设供电接口 | 接口标识 | 供电能力 | 适用设备 | 保护措施 | |----------|----------------|-------------------------|------------------------| | 5V OUT | 2A(峰值3A) | GPS/数传/相机云台 | 自恢复保险丝 | | 3.3V OUT | 500mA | 光流/超声波传感器 | TVS二极管阵列 | | SERVO RAIL | VBAT直连 | 舵机/大功率负载 | 独立MOS开关控制 | --- ### 三、关键电源电路设计 1. **电源模块(PM)选型规范** - 必须支持mavlink电池状态协议 - 电压采样精度要求: $$ \varepsilon \leq \pm0.1V \quad (0-50V范围) $$ - 典型方案:CUAV HV-PM / Holybro PM07 2. **多设备供电时序控制** ```c // 在启动脚本中定义供电顺序 px4_io start // 先启动IO板 sleep 1 sensors start // 再启动传感器 ``` --- ### 四、典型问题解决方案 1. **电压波动导致飞控重启** - 检查项: - 电源模块滤波电容(推荐470μF钽电容) - 电机启停时的电压跌落(应<1.5V) 2. **外设供电不足** - 扩展方案: ```python # 添加外置BEC示例 bec = ExternalBEC(vin=VBAT, vout=5V, imax=5A) bec.connect(POWER2) ``` --- ### 五、安全设计规范 1. 必须实现: - 独立电压监控电路(过压保护点): $$ V_{cutoff} = 6.0V \quad (5V总线) $$ - 电流霍尔传感器采样: $$ I_{max} = \frac{V_{ref}}{R_{shunt}} \times G_{ain} $$ 例:ACS712(5A量程) 2. 禁止行为: - 同时使用飞控5V输出和外部BEC供电 - 在未隔离情况下并联不同电源 ---
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值