25

阿木币

3

精华

68 小时

在线时间

老司机

Rank: 2

发表于 2019-7-12 18:07:51 20887 浏览 6 回复

[入门教程] px41.6.2—控制Aux Out输出

本帖最后由 ariesys 于 2019-7-12 18:21 编辑

一、参考网址
官网:
3、System Startup ->Starting a custom mixer:https://dev.px4.io/v1.9.0/en/concept/system_startup.html
博客:

二、概念
       mixer.png
      PX4中mixer的结构如上图所示,mixer的作用是连接上层应用模块(例如姿态控制器解算的输出量)与底层硬件的执行机构输出(对应电机、舵机的PWM值)。mixer模块相当于隔离了上层应用模块与底层的硬件接口,在编写上层应用模块时不用担心控制量是输出给哪个电机,同时更改不同的mixer配置文件可以适应不同的机型而无需更改上层应用模块的代码。
      下面简单解释一下Mixer的映射关系,以常规X型四旋翼为例,主要解释辅助通道如何设置,主通道的mixer解析在参考博客《PX4中混控器Mixer的分析》中有详细解析。图2是官网给出的输出通道配置。辅助通道的输出与设置的遥控器RC AUX1/2/3对应,也就是复制了遥控器某一通道的值,在遥控器界面可以设置RC AUX1/2/3对应的遥控器通道。
       2.png
       通过地面站设置飞行器类型后,可以看到SYS_AUTOSTART参数变成了相应的数字,常规X型四旋翼编号是4001,与图2中对应。不同的机型有不同的编号。
       3.png
         4.png
      在Firmware/ROMFS/px4fmu_common/init.d中可以看到名为4001_quad_x文件,同时在启动脚本文件rcS中会启动对应的脚本文件,即4001_quad_x文件。
      if param compare SYS_AUTOSTART 0
     then
           ekf2 start
      else
           sh /etc/init.d/rc.autostart
      fi
      在4001_quad_x文件中,
       sh /etc/init.d/rc.mc_defaults #启动了多旋翼脚本文件
      set MIXER quad_x        #主通道输出配置文件名为quad_x
      set PWM_OUT 1234      #设置主通道输出数为4
      在rc.mc_defaults文件中,
         set MIXER_AUX pass     #辅助通道输出配置文件名为pass
      set PWM_AUX_RATE 50  #输出频率为50
      set PWM_AUX_OUT 1234 #设置输出通道数目为4
      在Firmware/ROMFS/px4fmu_common/mixers文件夹中可以找到对应的mix文件
       5.png
      在pass.aux.mix文件中,映射了辅助输出通道与控制组的关系。
       # AUX1 channel (selectRC channel with RC_MAP_AUX1 param)
         M: 1
      O:      10000 10000      0 -10000  10000
      S: 3 5  10000 10000      0 -10000  10000
      # AUX2 channel (select RC channelwith RC_MAP_AUX2 param)
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 3 6  10000 10000      0 -10000  10000
      # AUX3 channel (select RC channelwith RC_MAP_AUX3 param)
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 3 7  10000 10000      0 -10000  10000
      # FLAPS channel (select RC channelwith RC_MAP_FLAPS param)
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 3 4  10000 10000      0 -10000  10000
      对应的语法,官网上《Mixing and Actuators》有详细解释,这里给出简单的解释
      M: <control count>
      O: <-ve scale> <+vescale> <offset> <lower limit> <upper limit>
      S: <group> <index><-ve scale> <+ve scale> <offset> <lower limit><upper limit>
      一组M: + O:代表一组通道,S:语法定义了该通道与控制组的关系,例如在AUX1上S: 3 5 ****就是把AUX1通道映射到了控制组3的5号变量上,根据官网给出的控制组3定义如下,把AUX1映射给了RC aux1变量。
      Control Group #3 (Manual Passthrough)
      0: RC roll
      1: RC pitch
      2: RC yaw
      3: RC throttle
      4: RC mode switch
      5: RC aux1
      6: RC aux2
      7: RC aux3

       以上就把底层的输出通道与控制组映射起来了,下面看如何在上层模块部分赋值控制组中的变量,在Firmware/msg/文件夹中actuator_control.msg消息中,
      # TOPICS actuator_controlsactuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3
      # TOPICSactuator_controls_virtual_fw actuator_controls_virtual_mc
       该该消息可用来发布actuator_controls、actuator_controls_0等消息,其中actuator_controls_0对应0号控制组,依次类推actuator_controls_3对应control group3。全局搜索actuator_controls_3,在Firmware/src/modules/sensors/rc.update.cpp文件中,
       /*copy from mapped manual control to control group 3 */
     structactuator_controls_s actuator_group_3 = {};
     actuator_group_3.timestamp= rc_input.timestamp_last_signal;
     actuator_group_3.control[0]= manual.y;
     actuator_group_3.control[1]= manual.x;
     actuator_group_3.control[2]= manual.r;
     actuator_group_3.control[3]= manual.z;
     actuator_group_3.control[4]= manual.flaps;
     actuator_group_3.control[5]= manual.aux1;
     actuator_group_3.control[6]= manual.aux2;
     actuator_group_3.control[7]= manual.aux3;
     /* publishactuator_controls_3 topic */
      orb_publish_auto(ORB_ID(actuator_controls_3),&_actuator_group_3_pub, &actuator_group_3, &instance,ORB_PRIO_DEFAULT);
       将manual.aux1赋值给了actuator_group_3.control[5]与pass.aux.mix设置的相对应,即根据actuator组号发布对应的控制组变量赋值。
       同样,在mc_att_control_main.cpp中,将姿态控制的输出赋值到_actuators_0数组。
      /* publishactuator controls */
     _actuators.control[0]= (PX4_ISFINITE(_att_control(0))) ? _att_control(0) : 0.0f;
     _actuators.control[1]= (PX4_ISFINITE(_att_control(1))) ? _att_control(1) : 0.0f;
     _actuators.control[2]= (PX4_ISFINITE(_att_control(2))) ? _att_control(2) : 0.0f;
     _actuators.control[3]= (PX4_ISFINITE(_thrust_sp)) ? _thrust_sp : 0.0f;
     orb_publish(_actuators_id,_actuators_0_pub, &_actuators);
      官网定义的ControlGroup0如下:
      Control Group #0 (FlightControl)
      0: roll (-1..1)
      1: pitch (-1..1)
      2: yaw (-1..1)
      3: throttle (0..1 normalrange, -1..1 for variable pitch / thrust reversers)
      4: flaps (-1..1)
      5: spoilers (-1..1)
      6: airbrakes (-1..1)
      7: landing gear (-1..1)
       以上解释了图1中的mixer结构关系,下面改写代码通过设置AUX通道的值来完成控制舵机、PWM继电器等操作。

三、实验效果
      实验目的:利用AUX输出通道控制PWM继电器模块。
      实验设备:
       硬件连接图如下:
       pwm.png
      实验步骤:
       1、改写mix文件:根据官网《Gimbal Control Setup》及《System Startup ->Startinga custom mixer》介绍,可以不用修改Firmware中的pass.aux.mix文件来重新设置aux的输出,通过在pixhawk的sd卡的根目录上建立一个etc的文件夹,在etc文件夹中创建mixers文件夹和config.txt文件,在mixers中创建名为mount.aux.mix文件。
       7.png
      mount.aux.mix文件内容如下,这里我们用控制组2的4、5、6通道映射AUX:
      # AUX1
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 2 4  10000 10000      0 -10000  10000
      # AUX2
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 2 5  10000 10000      0 -10000  10000
      # AUX3
      M: 1
      O:      10000 10000      0 -10000  10000
      S: 2 6  10000 10000      0 -10000  10000
       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
       插回sd卡即可。
2、改写代码:
       在mc_att_control_main.cpp仿照actuator0新建一组actuator2的相关变量。
      1)在class MulticopterAttitudeControl类中添加变量:
      orb_advert_t  _actuators_2_pub;      
      orb_id_t_actuators_id2;   
      bool     _actuators_2_circuit_breaker_enabled;
      structactuator_controls_s           _actuators2;         
       2)在MulticopterAttitudeControl::MulticopterAttitudeControl() 构造函数中初始化:
       _actuators_2_pub(nullptr),
      _actuators_id2(nullptr),
      _actuators_2_circuit_breaker_enabled(false),
      _actuators2{},
       3)在MulticopterAttitudeControl::vehicle_status_poll()中赋值id号,控制组号:
       _actuators_id2= ORB_ID(actuator_controls_2);
       4)在MulticopterAttitudeControl::task_main()中赋值、发布消息:
     _actuators2.control[4]= -1.0f;//对应1000us最低值
     _actuators2.control[5]= 0.0f;//对应1500us
     _actuators2.control[6]= 1.0f;//对应2000us最高值
     _actuators2.timestamp= hrt_absolute_time();
     _actuators2.timestamp_sample= _ctrl_state.timestamp;

     if(!_actuators_2_circuit_breaker_enabled) {
         if(_actuators_2_pub != nullptr) {
              orb_publish(_actuators_id2,_actuators_2_pub, &_actuators2);
         } else if(_actuators_id2) {
             _actuators_2_pub= orb_advertise(_actuators_id2, &_actuators2);
         }
     }
       编译、烧写代码。
     实验效果:
       上电后,按下安全开关,通过QGC可以看到servo1/2/3_raw分别赋值1000/1500/2000。
       PWM输出.PNG
      插上舵机测试一下:
       舵机实验.png
      插上推拉式电磁铁测试:
       电磁铁实验.png
      插上充电型电磁铁测试:
       电磁铁实验2.png
      当然官网上也介绍了如何通过MAVLINK控制AUX输出,筒子们可以任意选择。





扫一扫浏览分享
回复

使用道具 举报

25

阿木币

3

精华

68 小时

在线时间

老司机

Rank: 2

 楼主| 发表于 2021-1-11 21:04:12
mlsd 发表于 2020-12-25 19:56
您好,您的文章对我帮助很大。但是我还有个问题,如果不用pwm继电器,把舵机直接接在飞控板的aux口上,可以 ...

不好意思,不经常来,可以驱动舵机,最好给AUX单独供个电
回复 点赞 1

使用道具 举报

202

阿木币

0

精华

373 小时

在线时间

版主

Rank: 7Rank: 7Rank: 7

发表于 2019-7-13 09:54:37
好详细的好文章,实验的全过程。但为啥不用最新的PX4 1.8 1.9 还用1.6.2呢。。想不通
回复 点赞

使用道具 举报

25

阿木币

3

精华

68 小时

在线时间

老司机

Rank: 2

 楼主| 发表于 2019-7-13 11:50:24
maxiou 发表于 2019-7-13 09:54
好详细的好文章,实验的全过程。但为啥不用最新的PX4 1.8 1.9 还用1.6.2呢。。想不通
...

{:2_27:}主要是项目用的1.6.2的版本,项目做了一年半了,那时候用的1.6.2的版本改了一些代码在上面,就一直用着这个版本了。。。{:2_27:}
回复 点赞

使用道具 举报

139

阿木币

0

精华

287 小时

在线时间

管理员

Rank: 9Rank: 9Rank: 9

发表于 2019-7-15 09:11:30
好文
我不为己,谁人为我,但我只为己,那我又是谁?
回复

使用道具 举报

4

阿木币

0

精华

6 小时

在线时间

应届白菜

Rank: 1

发表于 2019-12-27 16:19:34
如果我不想用PWM继电器,只想给个高电平出去控制电磁铁,该怎么改呢?
回复 点赞

使用道具 举报

11

阿木币

0

精华

14 小时

在线时间

老司机

Rank: 2

发表于 2020-12-25 19:56:33
您好,您的文章对我帮助很大。但是我还有个问题,如果不用pwm继电器,把舵机直接接在飞控板的aux口上,可以驱动舵机吗?我之前在main口中做了类似尝试,但是舵机毫无反应,当然频率是调到50hz了。期待您的回答,打扰了
回复 点赞

使用道具 举报

返回列表
您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

快速回复 返回顶部 返回列表