PX4 ---- Mixer

Mixer (混合控制)

作用

经过位置控制和姿态控制后,控制量通过 actuator_controls发布,其中 control 数组存放了四个的控制量。(roll, yaw, pitch , throttle) 这四个量投影到不同的轴臂上,投影关系即是混控矩阵。

换句话说,混控确定了飞机的控制输出(yaw, roll, pitch)映射到飞机各个 PWM 通道输出的关系。(例如电调)

输入

混控的输入来自控制组(control group)。这些大多是预先定义好的,参见此处。在混控文件中会确定各个输出通道是由控制组中的通道加权求和得到。

输出

由于不同硬件的物理接口不同,所以在混控中不会显式指定输出的物理通道。而是通过混控文件的名称推断。(mainaux)。
ROMFS/px4fmu_common/mixer 存放了不同机型的混控文件 *.main.mix*.aux.mix

pixhawk4 上,前者对应的是 I/O PWM OUTPUT,对应着分电板上电机控制的输出。后者对应 FMU PWM OUTPUT。

空混控器:接受输入,输出0。(用于占位)

由于每一个 Block 按次序代表一路输出,空混控代表这一路没有输出。

简单混控:将多通道的控制量进行混合(eg. 叠加)。

M:<control mount>
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
S: <group> <index> <ve scale> <offset> <lower limit> <upper limit>

此处有详细的解释。说明:

  1. 都是放大 10000 倍。(10000 --> 1, 5000 --> 0.5)
  2. <-ve scale><+ve scale> 代表如果是负数,则乘 <-ve> 否则乘 <+ve>。所以
O:      -10000  -10000      0 -10000  10000

代表将其反向。(无论正负都乘 -1)

每一个 block 对应一个输出通道。block 确定了选取的 control group 和权值。最后作为输出。

装载混控文件

在飞机的配置文件里面指定装载的混控文件。配置文件在 ROMFS/px4fmu_common/init.d/airframes 下。

使用 set MIXER XXXX 装载 XXXX.main.mixset MIXER_AUX YYYY 装载 YYYY.aux.mix

多旋翼和固定翼默认装载 pass.aux.mix 将遥控器映射到辅助通道输出。

Mavlink Console中,使用 mixer load <device> <file> 装载文件。/dev 下 PWM 有 /dev/pwm_output0(FMU)与 /dev/pwm_output1 (IO)。 装载后,在 uorb 中 actuator_control_xx 代表相应的 Control Group 组。 actuator_outpus 代表两组 PWM 输出。

MAVROS

mavros 中有 Actuator_Control 话题。

注意只有在 OFFBOARD 模式下才有用。第三组 Manual Passthrough 与遥控器通道相同,使用 MAVROS 会冲突,RCUpdateMavlink Receiver 会同时向 actuator_control_3 上发布,导致舵机抖动。

代码解析

  1. 读取 urob 中 actuator_control_x 的消息,此处
if (_control_subs[i].copy(&_controls[i]))
  1. 调用混控组。此处
const unsigned mixed_num_outputs = _mixers->mix(outputs, _max_num_outputs);
  1. 矫正数值。由 [-1, 1] --> [-1000, 1000],outputs 为输出的 PWM。
output_limit_calc(_throttle_armed, armNoThrottle(), mixed_num_outputs, _reverse_output_mask,
			  _disarmed_value, _min_value, _max_value, outputs, _current_output_value, &_output_limit);
  1. 输出到硬件。_interface 可以指向 UAVCAN 或者 PWMOut
if (_interface.updateOutputs(stop_motors, _current_output_value, mixed_num_outputs, n_updates)) {...}

PWM Output
PWM 本质上就是设置始终 CCR 寄存器的值。

总结

依据 control group 确定混控输入来源编写混控文件。不用的 PWM 路用空混控占位。

示例

MAIN

定义了四路输出,其中第三路没有输出。来源此处

Delta-wing mixer for PX4FMU
===========================

Designed for Wing Wing Z-84

This file defines mixers suitable for controlling a delta wing aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
assumed to be unused.

Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).

See the README for more information on the scaler format.

Elevon mixers
-------------
Three scalers total (output, roll, pitch).

On the assumption that the two elevon servos are physically reversed, the pitch
input is inverted between the two servos.

The scaling factor for roll inputs is adjusted to implement differential travel
for the elevons.

M: 2
S: 0 0  -6000  -6000      0 -10000  10000
S: 0 1   6500   6500      0 -10000  10000

M: 2
S: 0 0  -6000  -6000      0 -10000  10000
S: 0 1  -6500  -6500      0 -10000  10000

Output 2
--------
This mixer is empty.

Z:

Motor speed mixer
-----------------
Two scalers total (output, thrust).

This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
range.  Inputs below zero are treated as zero.

M: 1
S: 0 3      0  20000 -10000 -10000  10000

AUX

定义了四路 AUX 输出。源码见此处

# Manual pass through mixer for servo outputs 1-4

# AUX1 channel (select RC channel with RC_MAP_AUX1 param)
M: 1
S: 3 5  10000  10000      0 -10000  10000

# AUX2 channel (select RC channel with RC_MAP_AUX2 param)
M: 1
S: 3 6  10000  10000      0 -10000  10000

# AUX3 channel (select RC channel with RC_MAP_AUX3 param)
M: 1
S: 3 7  10000  10000      0 -10000  10000

# FLAPS channel (select RC channel with RC_MAP_FLAPS param)
M: 1
S: 3 4  10000  10000      0 -10000  10000
  • 6
    点赞
  • 40
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值