APM+ 添加的代码说明

飞控开发

注意:这篇文章简绍的部分可能已过期,最新的以Github为准
这里说明我们hack了哪些代码,以及代码的简要说明。还是以多旋翼为例。固定翼的差不多,只是个别地方不一样。
添加的OSD主要代码都在文件夹./ardupilot/libraries/AP_OSD目录下。
1)AP_OSD_Var.h .cpp只是保存一些变量,比如要在屏幕上那个位置显示显示什么。初期写的时候分开了,其实没必要,可以移到AP_OSD_MAX7456.h里去,可能还能换点空间。
比如_panSpeed_XY[2];就是把速度显示在哪个位置。我们在cpp文件里写死了_panSpeed_XY[0] = 1; _panSpeed_XY[1] = 8;就是第1行,第8列。
另外的一些就是保存飞行数据的实际值。
miniosd有个配置工具很方便地修改这些位置,这些参数都是保存在芯片rom里。5imx上面泡泡老师写了很多关于miniosd的文章,大家可以参考。这里程序写死的原因是最大兼容原版APM固件,最低程度的修改而不影响原版固件。当然最大的原因是坑爹的2560芯片容量太小了,也不允许我们做过多的修改。后面还会有说明,我们为了把OSD加进去,注释掉一些不常用的代码。
2)AP_OSD_Stream.h .cpp只是为了可以使用printf这个函数来写max7456。
3)AP_OSD_MAX7456.h .cpp这个就是OSD的主要处理了
包括:
3-1)定义一些可以在地面站修改的参数。就是要不要显示那个东西。
3-2)max7456和2560是通过SPI通讯的,这里包括了max7456的初始化,以及读写操作。
3-3)AP_OSD_MAX7456::updateScreen()就是不断的更新屏幕上的值。这里我们把显示分为三个不同刷新频率,比如横滚角,俯仰角,水平线我们是10HZ(0.1秒)更新一次。而像电池信息我觉得不是特别需要实时,就1HZ(1秒)更新一次。
3-4)要写一些东西到7456,一般就是要4个函数。
setPanel(列,行); -------->要在哪个位置写
openPanel(); -------->告诉7456开始写了
printf("aaa"); -------->要写什么,因为我们重载了printf,所以这里会调用AP_OSD_MAX7456::write 而不是系统IO输出
closePanel(); -------->告诉7456我们写好了。
3-5)write_NVM就是更新7456的字库。
3-6)因为2560的SPI连了好几个设备,比如气压计,MPU6000,所以我们要操作7456前一定要先看看能不能抢到操作权限。_spi_sem->take()和_spi_sem->take_nonblocking()就是这个作用,使用完一定要调用_spi_sem->give();这样其他设备才能用SPI总线。_spi->cs_assert(); 就是片选拉低,_spi->cs_release();就是片选拉高。
这个文件看着很长,其实大多数都是业务处理逻辑,核心部分就是7456的SPI操作部分。
好了,以上代码都是新添加的,并没有修改APM原来的代码。那么下面主要是修改了APM的代码。
1)SPI管脚配置
./libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp
在APM2SPIDeviceManager::init函数的最后里添加了7456的SPI初始代码,不能把这段代码放在MPU6000初始化之前的,原因函数里有注释。
/* max7456 cs is on Arduino pin 53, PORTG3 */
AVRDigitalSource* max7456_cs = new AVRDigitalSource(_BV(3), PG);
/* max7456: run clock at 8MHz in high speed mode and 512kHz for low
* speed */

_max7456 = new AVRSPI0DeviceDriver(max7456_cs, SPI0_SPCR_500kHz, SPI0_SPCR_8MHz, SPI0_SPSR_8MHz);
_max7456->init();


_max7456这个参数在SPIDriver.h里添加
private:
AVRSPI0DeviceDriver* _mpu6k;
AVRSPI0DeviceDriver* _ms5611;
AVRSPI0DeviceDriver* _optflow_spi0;
AVRSPI0DeviceDriver* _max7456;


在函数APM2SPIDeviceManager::device里也加上7456部分。AP_HAL::SPIDevice_MAX7456这个变量在AP_HAL_Namespace.h里添加,如下:
enum SPIDevice {
      SPIDevice_Dataflash,
      SPIDevice_ADS7844,
      SPIDevice_MS5611,
      SPIDevice_MPU6000,
      SPIDevice_ADNS3080_SPI0,
      SPIDevice_ADNS3080_SPI3,
      SPIDevice_MAX7456,
};


2)主文件\ArduCopter\ArduCopter.pde里的修改(行数可能会不一样,这里仅参考)
包含头文件(废话?还是说一下吧)#139行
#include "AP_OSD_MAX7456.h"


定义7456的全局变量 #239
static AP_OSD_MAX7456 osdMax7456;      


添加定时处理函数 #879,我们放在靠后一点吧。毕竟OSD不是那么重要。少做一两次处理关系不大
{ write_osd,                       10,           50 },


实际的定时处理函数 #929,这个函数就是把要显示的值取出来,然后最后调用7456的updateScreen()函数,来在屏幕上显示一些东西。
static void write_osd(void)
{
if(osd_should_run <0)
      return;
osdMax7456._osd_vars->_BatteryVol = battery.voltage();
osdMax7456._osd_vars->_BatteryCurrent = battery.current_amps() * 100;
osdMax7456._osd_vars->_BatteryPercent = battery.capacity_remaining_pct();
osdMax7456._osd_vars->_BatteryConsum =   battery.current_total_mah();       //Total current consume since start up in amp/h
osdMax7456._osd_vars->_GPSSats = g_gps->num_sats;
osdMax7456._osd_vars->_GPSLongitude = g_gps->longitude / 10000000.0f;
osdMax7456._osd_vars->_GPSLatitude = g_gps->latitude / 10000000.0f;
osdMax7456._osd_vars->_GPSLongitudePrint = g_gps->longitude / 10000000000.0f;
osdMax7456._osd_vars->_GPSLatitudePrint = g_gps->latitude / 10000000000.0f;
osdMax7456._osd_vars->_groundSpeed = ahrs.groundspeed();
osdMax7456._osd_vars->_heading = (ahrs.yaw_sensor / 100) % 360;
osdMax7456._osd_vars->_throttle = g.rc_3.servo_out/10;
osdMax7456._osd_vars->_altitude = current_loc.alt / 100.0f;
//float climbRate = climb_rate / 100.0f;
osdMax7456._osd_vars->_pitch = ahrs.pitch * 57.2957795131;           //to degree *180/pi
osdMax7456._osd_vars->_roll = ahrs.roll * 57.2957795131;               //to degree *180/pi
//int8_t yaw = ahrs.yaw * 57.2957795131;               //to degree *180/pi
osdMax7456._osd_vars->_WPDirection = wp_bearing;
osdMax7456._osd_vars->_WPDistance = wp_distance;
//uint8_t wayPointNum = mission.get_current_nav_index();
osdMax7456._osd_vars->_homeDirection = home_bearing;
osdMax7456._osd_vars->_homeDistance = home_distance;
osdMax7456._osd_vars->_flyMode = control_mode;
osdMax7456._osd_vars->_startTime = hal.scheduler->millis()*0.001f;
osdMax7456.updateScreen();
}


3)对上面我们添加的全局变量初始化,是在\ArduCopter\system.pde里的static void init_ardupilot()里。我们还是放最后吧,尽量不干扰其他重要的处理,这个函数的最后加上:
osdMax7456.init();
osd_should_run = 1;


4)添加可以在地面站里修改的参数。注意添加参数的时候一定要小心,不要把原来的参数位置覆盖掉,APM官网有文章:http://dev.ardupilot.com/wiki/ ... eter/
\ArduCopter\parameters.h文件 #101行添加
k_param_osdMax7456,                             //41


\ArduCopter\Parameters.pde文件#1123行添加
// OSD driver
// @Group: OSD_
// @Path: ../libraries/AP_OSD/AP_OSD_MAX7456.cpp
GOBJECT(osdMax7456, "OSD_", AP_OSD_MAX7456),


这个真的很赞,完全体现了开源的优势,协议统一,可以不修改地面站。如果要修改可能要修改好多啊,missionplanner, APMPlanner,QGC等等。不像那些封闭的飞控,要定置一些东西还要学用他们的SDK,问题是还不一定能得到你想要的。打住,不说与代码无关的了。
5)更新MAX7456的字符集。这个是通过串口来更新的,更新程序就用miniosd的那个吧。因为我们只用了那个工具的这个功能,怕有人点了其他的按钮,所以我把其他的功能都删除了。只留一个更新字符集的功能。对固件代码来说,更新的部分如下:
\libraries\GCS_MAVLink\GCS.h里添加个变量和函数 #227行
//this allow us to detect if the user wanting upload max7456 fonts
uint8_t                 star_count;
void               uploadFont(mavlink_channel_t chan);


\ArduCopter\GCS_Mavlink.pde里函数GCS_MAVLINK::update(void)里 #877行添加
if (mavlink_active == 0 && (millis() - _cli_timeout) < 20000) {
              if (c == '*') {
                      star_count++;
              }
              else if(c != '\n' && c != '\r'){
                      star_count = 0;
              }
              if(star_count>=3){
                      uploadFont(chan);
                      star_count = 0;
              }
}


就是串口收到3个*号的时候认为是要传字符了。这个把miniosd的按个配置工具也稍微修改了。不是发3个回车,那样容易和mavlink混淆。
\ArduCopter\GCS_Mavlink.pde里实现函数 uploadFont(mavlink_channel_t chan); #940行
这个都是miniosd抄来的。很长不贴了。

6)注释掉的功能。坑爹的2560,芯片容量已经到极限了,加了OSD功能,代码太大,烧不进去了。所以忍痛割爱吧。把一些功能注释掉吧。如果需要,可以改回来,把其他的注释掉。总有不需要的吧^_^,你全要,那也没办法了,不要OSD的话,把那个static void write_osd(void)函数里的东西都注释掉就行了。
\ArduCopter\APM_Config.h里我把MOUNT注释掉了。换了8K的空间。我是没用过这个功能。你们需要吗?自己改回来吧。

7)还有那些啊,可能是有些头文件要添加吧。不太记得了。

10 个评论

写的很详细
因为APM基于Arduino,所以代码体积有点大...
会不会用其他编译方式会好点呢,请指教。我现在把代码放到github上面,基于3.2版本来改动。还没弄好
嘿嘿,我只是菜鸟。arduino的函数很方便,但是目标文件编译出来偏大,我记得有个小体积的库,如果移植的话,体积会不会小一些呢。。
我也是菜鸟,代码基本都是miniosd抄来的,哈哈。我正在编译3.2,还有把github弄好。到时候,你check一份试试。大家一起研究研究
赞一个,Mount功能是用来做舵机云台增稳的,如果用了自带无刷控制板的云台也可以不要
APM 的代码是跨平台的 , 针对 AVR 版本的早就已经不再使用Arduino 库了, 你说的那是很早以前的事情了
好的,看来我的认知有点落后了
顶楼主,一直都是看官网的wiki,今天偶然发现了这个网站 我们自己也有中文网了 真是激动啊
一直在看wiki啊

要回复文章请先登录注册