PX4自定义混控器

文章目录

  • 前言
  • 混控器简介
  • 混控器的启动
  • 自定义混控器
  • 参考:

前言

上一篇我对PX4的控制和输出的全流程都进行了较为详尽的分析,本来想着之后的研究主要在四旋翼控制算法上,不会定义啥新机型,混控器的部分就不再深究了。但是好奇心害死人呀,又捣鼓了一两天来实践了一下自定义混控器,现在也把大概流程记录一下,说不定啥时候就用上了。首先需要说明一下,PX4对于一些飞控硬件的支持并不是很好。比如cuav的nano。实践PX4代码中的混控器部分,找到了一些好帖子,兴致冲冲的跟着做,最后发现AUX没有按照我在sd卡里设置的混空器那样去执行。找了一晚上原因,终于!我在PX4官方手册的nano的说明部分发现了下图。啊这!如果这几个引脚不是取名为A1,A2,A3的话,我想我可能早就察觉到了不对劲了,这实在太坑了,记录一下,避免以后再犯这样的错误!同样pixhawk4 mini 上面的4个cap口,PX4目前也是不能用的。这样一看ardupilot还是猛呀,支持的功能确实是多。
PX4自定义混控器_第1张图片

混控器简介

PX4进行设计的时候就非常模块化,将每个部分尽可能的进行分离,保证各个部分专注自己的事情可以很好地被复用和被修改,混控器也是这样的设计。对于一般的无人机而言,我们都将其假定为刚体模型,最终的控制器输出的控制量本质上就只有三个方向的力矩和三个方向的力。但是对于不同的机型,我们的执行器是不一样的,那么就需要一个帮手来将原始的控制信号分配到各个执行器。这部分的工作就正是混控器要做的。也就是说对于不同的机型,混控器只要做不同的输出设置就可以复用相同的控制器了。这样的设计就非常的合理了。关于混控器的更详细说明,请移步我的这篇文章

混控器的启动

PX4的启动是从nuttx完成初始化后,运行rcS脚本开始的,也许玩过单片机的朋友会觉得这样很多余很麻烦,但是一旦你熟悉一下后就会觉得,在一个庞大的工程项目中,这样的操作是一个很好的选择。

启动的流程大致如下:

  • 系统运行rcS脚本到这里sh /etc/init.d/rc.autostart

  • rc.autostart中根据系统参数中机型的设置参数,赋值AIRFRAME(假设这里是4001_quad_x),然后运行. /etc/init.d/airframes/${AIRFRAME}

  • 4001_quad_x执行如下内容

sh /etc/init.d/rc.mc_defaults  //执行脚本
set MIXER quad_x   //设置 main通道的混控器为quad_x,之后将加载quad_x.main.mix
set PWM_OUT 1234  //设置main通道的输出口
  • rc.mc_default 内容如下
set VEHICLE_TYPE mc  #设置机型名称
param set-default IMU_GYRO_RATEMAX 800
param set-default NAV_ACC_RAD 2
param set-default RTL_RETURN_ALT 30
param set-default RTL_DESCEND_ALT 10
param set-default PWM_MAIN_MAX 1950
param set-default PWM_MAIN_MIN 1075
param set-default PWM_MAIN_RATE 400 
param set-default GPS_UBX_DYNMODEL 6  //设置一些输出的参数
set MIXER_AUX pass  //设置 AUX通道的混控器为pass,之后将加载pass.aux.mix
set PWM_AUX_OUT 1234 //设置AUX通道的输出口
  • quad_x.main.mix加载主混控器
R: 4x 10000 10000 10000 0

AUX1 Passthrough
M: 1
S: 3 5  10000  10000      0 -10000  10000

AUX2 Passthrough
M: 1
S: 3 6  10000  10000      0 -10000  10000
#显然,这里定义了一个四旋翼的混控器,还定义了5通道和6通道为辅助输出通道,根据控制组信息也可清楚看到其映射情况
#Control Group #3 (Manual Passthrough)
#    0: RC roll
#    1: RC pitch
#    2: RC yaw
#    3: RC throttle
#    4: RC mode switch (Passthrough of RC channel mapped by RC_MAP_FLAPS)
#    5: RC aux1 (Passthrough of RC channel mapped by RC_MAP_AUX1)
#   6: RC aux2 (Passthrough of RC channel mapped by RC_MAP_AUX2)
#    7: RC aux3 (Passthrough of RC channel mapped by RC_MAP_AUX3)
  • 加载pass.aux.mix混控器,如下所示,我们也可以很清楚地看到这四个AUX通道将映射到RC_MAP_FLAPS,RC_MAP_AUX1,RC_MAP_AUX2,RC_MAP_AUX3
M: 1
S: 3 5 10000 10000 0 -10000 10000
M: 1
S: 3 6 10000 10000 0 -10000 10000
M: 1
S: 3 7 10000 10000 0 -10000 10000
M: 1
S: 3 4 10000 10000 0 -10000 10000

如此一来混控器就启动完毕了,根据上面的分析大家也很清楚只要脚本稍微修改就可以构造出新的机型。

自定义混控器

有操作系统的好处就在于,我们并不需要去修改源代码然后再编译去获得一个拥有新机型的固件,我们只需要在飞控的SD卡中添加一些脚本即可!

上述的启动过程只是常规的启动过程,实际上在脚本运行时还有另一个路径:

set FCONFIG /fs/microsd/etc/config.txt

#这里省略大量代码.....

# Set parameters and env variables for selected AUTOSTART.
	#
	if ! param compare SYS_AUTOSTART 0
	then
		sh /etc/init.d/rc.autostart
	fi

	#
	# Override parameters from user configuration file.
	#
	if [ -f $FCONFIG ]
	then
		echo "Custom: ${FCONFIG}"
		sh $FCONFIG
	fi

可以看到如果操作系统检查到/fs/microsd/etc/config.txt存在,那么就会执行里面的内容从而可以覆盖在rc.autostart设置的一些参数,当然混控器也包含在内。

我们可以在SD建立下面三个文件来对飞控进行一些自定义设置:

  • /fs/microsd/etc/config.txt
  • /fs/microsd/etc/extras.txt
  • /fs/microsd/etc/mixers/NAME_OF_MIXER

extras.txt的作用主要是去调用飞控的一些应用程序来做一些应用的修改,比如添加飞控发送的mavlink数据。config.txt和mixers文件夹则是自定义混控器的地方了。

这里我的测试脚本如下:

  • etc/config.txt
set MIXER_AUX mount
set PWM_AUX_OUT 1234
set PWM_AUX_DISARMED 1500
set PWM_AUX_MIN 1000
set PWM_AUX_MAX 2000
set PWM_AUX_RATE 50

set MIXER mine
set PWM_MAIN_MAX 1950
set PWM_MAIN_MIN 1075
set PWM_MAIN_RATE 300
  • etc/mixers/mine.main.mix
# MAIN_1
M: 1
O:      10000 10000      0 -10000  10000
S: 0 0  10000 10000      0 -10000  10000
# MAIN_2
M: 1
O:      10000 10000      0 -10000  10000
S: 0 1  10000 10000      0 -10000  10000
# MAIN_3
M: 1
O:      10000 10000      0 -10000  10000
S: 0 2  10000 10000      0 -10000  10000
  • etc/mixers/mount.aux.mix
# AUX1
M: 1
O:      10000 10000      0 -10000  10000
S: 0 0  10000 10000      0 -10000  10000
# AUX2
M: 1
O:      10000 10000      0 -10000  10000
S: 0 1  10000 10000      0 -10000  10000
# AUX3
M: 1
O:      10000 10000      0 -10000  10000
S: 0 2  10000 10000      0 -10000  10000

将这些写入sd卡后,插入飞控并启动,以上混空器就可以被执行了。最终的效果就是MAIN和AUX的1,2,3通道都将分别输出控制组0的 roll, pitch, yaw的控制信号。也就是只要在各个轴线上晃动飞控,舵机就会做出相应的动作。

参考:

阿木论坛优贴
PX4开发者手册

你可能感兴趣的:(arm,stm32)