Pixhawk 基础

资源

Lorenz 最近重新整理了一下 wiki,非常值得一个一个页面浏览一遍。

工具链安装

主要是安装依赖并将用户加入 dialout 组及 plugdev

1
2
$ sudo usermod -a -G dialout $USER
$ sudo usermod -a -G plugdev $USER

然后安装 arm-gcc,注意网上可以找到一个 ppa,但是不要使用,因为版本不对。

1
2
3
4
5
6
7
8
9
10
$ sudo apt-get install ia32-libs python-serial python-argparse grep
$ sudo apt-get install flex bison libncurses5-dev autoconf texinfo build-essential libtool zlib1g-dev genromfs git wget
$ pushd .
$ cd ~
$ wget https://launchpadlibrarian.net/174121628/gcc-arm-none-eabi-4_7-2014q2-20140408-linux.tar.bz2
$ tar -jxf gcc-arm-none-eabi-4_7-2014q2-20140408-linux.tar.bz2
$ exportline="export PATH=$HOME/gcc-arm-none-eabi-4_7-2014q2/bin:\$PATH"
$ if grep -Fxq "$exportline" ~/.profile; then echo nothing to do ; else echo $exportline >> ~/.profile; fi
$ . ~/.profile
$ popd

烧程序并上传固件

如果 NuttX 更新过

1
2
3
4
$ make distclean
$ make clean
$ make archives
$ make px4fmu-v2_default

否则

1
2
$ make clean
$ make px4fmu-v2_default

上传

1
$ make upload px4fmu-v2_default

经测试,这一步一定要先卸载 modemmanager

1
$ sudo apt-get remove modemmanager

系统启动

启动顺序由 /etc/init.d/rcS 控制,步骤:

  1. 检测硬件
  2. 加载传感器驱动
  3. 其他 apps

所有用于自动启动的脚本都位于 ROMFS/px4fmu_common/init.d/

  • 所以牛逼的人才自己写 etc/rc.txt,自己修改时改 etc/config.txtetc/extras.txt
  • 重刷固件的时候,SYS_AUTOCONFIG = 1,导致所有参数重置(包括这个变量)。
  • 重刷后依然想保留的配置(mixer, output mode, PWM range etc.),应该写在 etc/config.txt 里面。

The mavlink application sends and receives MAVLink packets on a serial port and translates them into the onboard object request broker structure.

app 功能

  • 航点管理 (waypoint management)
    1. 用户在地面站输入航点
    2. mavlink app 接收航点
    3. app 确定当前位置及当前激活航点的偏差判断是否到达
    4. 当前激活当点会作为位置控制器的输入
  • 参数更新 (updating of parameters)

使用

系统启动以后自动 TELEM1 (/dev/ttyS1) 开 mavlink。

  • 默认的波特率为 57600

如果希望用串口 (serial 4),需要自己手动启动或者加到启动脚本里。

1
nsh> mavlink start -d /dev/ttyS6 -b 460800

usb 口 (/dev/ttyACM0) 比较特殊,默认开的是一个 nsh,不发送 mavlink 信息。但是连上 QGC 以后,QGC 会通过 nsh 开 mavlink!

1
2
3
4
5
6
7
8
9
// https://github.com/mavlink/qgroundcontrol/blob/fc493d75c1e037e6d3919906c4b1a32ebe9cad91/src/comm/MAVLinkProtocol.cc#L189
// Send command to start MAVLink
// XXX hacky but safe
// Start NSH
const char init[] = {0x0d, 0x0d, 0x0d};
link->writeBytes(init, sizeof(init));
const char* cmd = "sh /etc/init.d/rc.usb\n";
link->writeBytes(cmd, strlen(cmd));
link->writeBytes(init, 4);

Mavlink 提供三种 log 功能。

1
2
3
mavlink_log_emergency(_fd, _str)
mavlink_log_critical(_fd, _str)
mavlink_log_info(_fd, _str)

这样子使用:

1
2
3
4
#include <mavlink/mavlink_log.h>
static int mavlink_fd;
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
mavlink_log_info(mavlink_fd, "[myapp] Hello, this is myapp talking.");
  • MAVLINK_LOG_DEVICE = “/dev/mavlink”
    • 这个设备由 mavlink_main.cpp 注册,其它模块只打开及写入
  • mavlink_log.h 由 mavlink 提供,不是 Pixhawk 的一部分

其它

Output Mixers

The output mixer defines how the controller output gets mapped to the motor and servo outputs.

  1. 不同飞机的 mixer 都放在 etc/mixers,文件夹内有 README 可以看文件格式定义
  2. 个人定制的 mixer 文件命名为 FMU_ABC.mix,然后通过 MIXER = FMU_ABC 来使用

Custom Model

etc/config.txt 内可以定制机架类型。如果要定制 a quadcopter with “+” configuration with ESCs connected to PX4IO and custom PWM range (1100…1900),大概写成这样:

1
2
3
4
5
6
7
8
9
# Generic Quadcopter +
set VEHICLE_TYPE mc
set MIXER FMU_quad_+
# PX4IO PWM output will be used by default
set PWM_OUTPUTS 1234 # Change parameters for the first 4 outputs
set PWM_RATE 400 # Set PWM rate to 400 Hz for better performance
set PWM_DISARMED 900 # Motors should stop at this PWM value
set PWM_MIN 1100 # Motors should spin at low, idle speed at this PWM value
set PWM_MAX 1900 # Motors should spin at max speed at this PWM value

Circuit Breakers

断流器 (Circuit Breakers) 用来在软件上屏蔽某些模块。

例如想省去每次上电需要按 safety switch 的步骤,就可以使 CBRK_IO_SAFETY = 22027