PX4垂直起降过程研究总结

tech2025-07-22  6

这篇博客只要对垂直起降过程和控制逻辑进行分析。 版本:V1.10.2 源码位置: ~src/modules/vtol_att_control/vtol_att_control_main.cpp ~src/modules/vtol_att_control/tiltrotor.cpp ~src/modules/vtol_att_control/mc_att_control_main.cpp ~src/modules/vtol_att_control/FixedwingAttitudeControl.cpp

1. 介绍

在垂起起降飞机中,固件里一共分了三类: standard:传统的升推结合的类型; tailsitter: 尾座式 tiltrotor: Y3类型的,前面是倾转旋翼,后面一个水平旋翼。 这里我们之研究tiltrotor类型。

2. vtol_att_control_main

这个主函数是对垂起控制的总体控制,任何类型飞机都走这个流程,区别就在于里面状态更新函数根据不同飞机不一样。 从上图可以看出,在垂起阶段飞控通过判断飞机类型对不同飞机进行操纵,然后再根据状态机实时更新飞机状态。 这里有几个注意点:

关于是否有操纵输入(actuators),这是在固定翼或者旋翼控制里面发布的,如果更新了就为真,没有发布就为假关于虚拟控制量(**_virtual_att_sp),以旋翼模式为例,在旋翼姿态控制主函数里面(mc_att_control::Run)有一个设置指令值发布的uorb ID,就在vehicle_status_poll里面进行了判断,如果是垂起飞机,指令值就先发布到虚拟控制量,到后面不同飞机模式更新(update_fw_state/update_mc_state/update_transition_state)的时候再拷贝到真实控制量里面。有很多函数为同构函数(类似于get_mode),需要根据不同的类对象进入,这个在类初始化里面就有判断,根据不同类型飞机实例化不同的对象。

3. tiltrotor.cpp

这一部分是对tiltrotor类型的飞机的具体控制,包括状态更新和控制输出分配。

3.1 update_vtol_state

这是对飞行状态更新流程判断,下面有几个注意点:

有两类飞行模式,vtol_mode是具体过程分别有:MC_MODE;FW_MODE;TRANSITION_FRONT_P1;TRANSITION_FRONT_P2;TRANSITION_BACK. _vtol_mode是再上面一级的封装,有ROTORY_MODE;FW_MODE;TRANSITION_TO_FW;TRANSITION_TO_MC;switch-case语句,如果case后面有break则结束switch,没有的话就进行下一个case,下面是一个例子 // map tiltrotor specific control phases to simple control modes switch (_vtol_schedule.flight_mode) { case vtol_mode::MC_MODE: _vtol_mode = mode::ROTARY_WING; break; case vtol_mode::FW_MODE: _vtol_mode = mode::FIXED_WING; break; case vtol_mode::TRANSITION_FRONT_P1: case vtol_mode::TRANSITION_FRONT_P2: _vtol_mode = mode::TRANSITION_TO_FW; break; case vtol_mode::TRANSITION_BACK: _vtol_mode = mode::TRANSITION_TO_MC; break; } 这里就很明显P1和P2阶段都被分到了TRANSITION_TO_FW模式,如果再看外围的话,TRANSITION_TO_FW和TRANSITION_TO_MC是一起控制。关于中断控制的逻辑(还不是很确定) 在垂起转平飞失败之后会进入到旋翼模式判断下的MC_MODE,如果固定翼过渡切回去的话还是会变成MC_MODE,也就是说不论怎么中断过渡过程都会变成旋翼模式。

3.2 update_transition_state

这个函数主要是控制旋翼倾转还有控制权重计算。 旋翼倾转由_tilt_control里面控制,根据时间变化 权重计算由下面策略计算,首先对符号进行说明: v a v_a va:当前飞行速度; v b v_b vb:权重开始变化时候的速度; v t v_t vt:转为固定翼的时候的速度; w r w_r wr:旋翼滚转权重; w y w_y wy:旋翼偏航权重; w p w_p wp:旋翼俯仰权重。 对于滚转通道,按照下面公式计算: w r = v a − v b v t − v b w_r=\frac{v_a-v_b}{v_t-v_b} wr=vtvbvavb 对于偏航通道,如果在偏航控制解除之前(ARSP_CTRL_DISABLE),偏航和滚转的权重相同。 对于俯仰通道,在过渡阶段控制指令为1,切到固定翼模式之后(FW_MODE)直接变成0。

4. 内环控制

前面讲的都是外环控制,至于内环姿态控制,有一个需要注意的点: 在旋翼阶段,姿态控制是由旋翼模态全权控制,但是在过渡阶段,角度率的指令值是由固定翼解算发布

在mc_att_control::Run中由下面一段判断

bool run_att_ctrl = _v_control_mode.flag_control_attitude_enabled && (is_hovering || is_tailsitter_transition);

这里run_att_ctrl只有在姿态控制开启并且飞机处于巡航或者是尾座式飞机的时候才会对姿态进行控制,如果不是的话,就直接读取角速率控制值:

else { /* attitude controller disabled, poll rates setpoint topic */ if (_v_rates_sp_sub.update(&_v_rates_sp)) { _rates_sp(0) = _v_rates_sp.roll; _rates_sp(1) = _v_rates_sp.pitch; _rates_sp(2) = _v_rates_sp.yaw; _thrust_sp = -_v_rates_sp.thrust_body[2]; }

但是由于这种情况下不发布角速率控制值,反而在固定翼里面发布,因为在固定翼里面有一个下面这个函数

FixedwingAttitudeControl::vehicle_control_mode_poll() { _vcontrol_mode_sub.update(&_vcontrol_mode); if (_vehicle_status.is_vtol) { const bool is_hovering = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_vehicle_status.in_transition_mode; const bool is_tailsitter_transition = _vehicle_status.in_transition_mode && _is_tailsitter; if (is_hovering || is_tailsitter_transition) { _vcontrol_mode.flag_control_attitude_enabled = false; _vcontrol_mode.flag_control_manual_enabled = false; } } }

在这个函数里面明确规定在巡航或者是尾座式飞机里面,_vcontrol_mode.flag_control_attitude_enabled = false; _vcontrol_mode.flag_control_manual_enabled = false; 因此在主函数Run里面就不对姿态进行控制,但是其他情况就会控制姿态并发布角速度的指令值,因此在旋翼角速率控制就会用到固定翼发布的指令。

5. 目前还存在的问题

遥控器切换模式时代码如何检测为什么过渡阶段一定是定高控制过度模式下旋翼模式控制有一个比重,固定翼模式的比重在哪里,如何融合的。
最新回复(0)