APM编译记录-基于OMNIBUSF4-V3飞控板

APM编译记录-基于OMNIBUSF4-V3飞控板

  • APM编译记录
    • Bootloader问题
    • 固件编译

APM编译记录

初次使用APM,根据博客文章以及结合官方教程摸索,发现和PX4还是有挺大差别的,目前系统已经换到chibios了,不是原来的nuttx。
感谢梦萦蓝天的教程
先给出参考的链接: 参考博主的帖子
APM官网教程
本记录是基于Ubuntu环境已经搭好并且编译环境也已搭建完成。

Bootloader问题

编译好apm的bootloader之后使用openocd连接jlink下载进飞控,然后使用 reset 复位之后 发现再也连接不上飞控了。
连接信息没有出现error 字眼,但在最后两行出现:

in procedure 'init' 
in procedure 'ocd_bouncer'

经过各种验证,是由于apm的omnibusf4目标基于omnibusf4pro目标的,而这个目标的hwdef_bl.dat里面没有配置 SWD导致 烧录后直接禁用掉了SWD功能,经过拉高boot0再上电然后可以连接上了,但没从根本上解决。
解决办法:在ardupilot/libraies/AP_HAL_ChibiOS/hwdef/omnibusf4pro目录下的hwdef_bl.dat文件最后面 加上下面两行

# debug 
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

重新编译BootLoader然后烧录,问题解决。

固件编译

编译正常使用一切正常,但想在VS Code里面debug 编译目标需要加–debug指令,编译出来的固件flash 超出了大约14K,解决办法是在ardupilot/build/omnibusf4下面的ldscript.ld文件修改固件最大容量

MEMORY
{
flash : org = 0x08010000, len = 960K
ram0 : org = 0x20000000, len = 131072
}

INCLUDE common.ld
修改为:

MEMORY
{
    flash : org = 0x08010000, len = 980K
    ram0  : org = 0x20000000, len = 131072
}

INCLUDE common.ld

固件容量从960K变为980K,重新编译没有问题,进行debug发现会死在加载不到1024K地址的错误提示信息,没办法,只能删减功能。APM利用宏定义的方式选择开启或关闭一些功能,并不像PX4那样利用cmake的路径包含方式。
修改的文件在ardupilot/ArduCopter目录下的APM_Config.h
原本它是注释掉了所有,我把一些给打开表明禁用掉这些功能。

// User specific config file.  Any items listed in config.h can be overridden here.

// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.

// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
#define LOGGING_ENABLED       DISABLED            // disable logging to save 11K of flash space
#define MOUNT                 DISABLED            // disable the camera gimbal to save 8K of flash space
#define AUTOTUNE_ENABLED      DISABLED            // disable the auto tune functionality to save 7k of flash
//#define AC_FENCE              DISABLED            // disable fence to save 2k of flash
#define CAMERA                DISABLED            // disable camera trigger to save 1k of flash
//#define RANGEFINDER_ENABLED   DISABLED            // disable rangefinder to save 1k of flash
//#define PROXIMITY_ENABLED     DISABLED            // disable proximity sensors
//#define AC_RALLY              DISABLED            // disable rally points library (must also disable terrain which relies on rally)
//#define AC_AVOID_ENABLED      DISABLED            // disable stop-at-fence library
//#define AC_OAPATHPLANNER_ENABLED DISABLED         // disable path planning around obstacles
//#define AC_TERRAIN            DISABLED            // disable terrain library
//#define PARACHUTE             DISABLED            // disable parachute release to save 1k of flash
//#define NAV_GUIDED            DISABLED            // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
#define OPTFLOW               DISABLED            // disable optical flow sensor to save 5K of flash space
#define FRSKY_TELEM_ENABLED   DISABLED            // disable FRSky telemetry
#define ADSB_ENABLED          DISABLED            // disable ADSB support
//#define PRECISION_LANDING     DISABLED            // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED        DISABLED            // disable beacon support
#define SPRAYER_ENABLED       DISABLED            // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED         DISABLED            // disable winch support
//#define GRIPPER_ENABLED       DISABLED            // disable gripper support
//#define RPM_ENABLED           DISABLED            // disable rotations per minute sensor support
//#define MAGNETOMETER          DISABLED            // disable magnetometer support
//#define STATS_ENABLED         DISABLED            // disable statistics support
//#define MODE_ACRO_ENABLED     DISABLED            // disable acrobatic mode support
//#define MODE_AUTO_ENABLED     DISABLED            // disable auto mode support
//#define MODE_BRAKE_ENABLED    DISABLED            // disable brake mode support
//#define MODE_CIRCLE_ENABLED   DISABLED            // disable circle mode support
//#define MODE_DRIFT_ENABLED    DISABLED            // disable drift mode support
//#define MODE_FLIP_ENABLED     DISABLED            // disable flip mode support
//#define MODE_FOLLOW_ENABLED   DISABLED            // disable follow mode support
//#define MODE_GUIDED_ENABLED   DISABLED            // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED   DISABLED      // disable guided/nogps mode support
//#define MODE_LOITER_ENABLED   DISABLED            // disable loiter mode support
//#define MODE_POSHOLD_ENABLED  DISABLED            // disable poshold mode support
//#define MODE_RTL_ENABLED      DISABLED            // disable rtl mode support
//#define MODE_SMARTRTL_ENABLED DISABLED            // disable smartrtl mode support
//#define MODE_SPORT_ENABLED    DISABLED            // disable sport mode support
//#define MODE_SYSTEMID_ENABLED DISABLED            // disable system ID mode support
//#define MODE_THROW_ENABLED    DISABLED            // disable throw mode support
//#define MODE_ZIGZAG_ENABLED   DISABLED            // disable zigzag mode support
//#define OSD_ENABLED           DISABLED            // disable on-screen-display support
//#define BUTTON_ENABLED        DISABLED            // disable button support

// features below are disabled by default on all boards
//#define CAL_ALWAYS_REBOOT                         // flight controller will reboot after compass or accelerometer calibration completes
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE   // disable mode changes from GCS during Radio failsafes.  Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
//#define ADVANCED_FAILSAFE     ENABLED             // enabled advanced failsafe which allows running a portion of the mission in failsafe events

// other settings
//#define THROTTLE_IN_DEADBAND   100                // redefine size of throttle deadband in pwm (0 ~ 1000)

//#define HIL_MODE              HIL_MODE_SENSORS    // build for hardware-in-the-loop simulation

// User Hooks : For User Developed code that you wish to run
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
//#define USERHOOK_VARIABLES "UserVariables.h"
// Put your custom code into the UserCode.cpp with function names matching those listed below and ensure the appropriate #define below is uncommented below
//#define USERHOOK_INIT userhook_init();                      // for code to be run once at startup
//#define USERHOOK_FASTLOOP userhook_FastLoop();            // for code to be run at 100hz
//#define USERHOOK_50HZLOOP userhook_50Hz();                  // for code to be run at 50hz
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop();        // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop();            // for code to be run at 3.3hz
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop();  // for code to be run at 1hz
//#define USERHOOK_AUXSWITCH ENABLED                        // for code to handle user aux switches
//#define USER_PARAMS_ENABLED ENABLED                       // to enable user parameters

重新编译发现固件小了二十多K左右,然后启用debug打断点测试成功。
打断点注意在程序必定会进去的地方打才能保证所操作的是对的,Copter.cpp文件的fast_loop()函数是一定会进去的,在里面打就好了。

初次入坑,陈述不对之处请朋友多多指正。

你可能感兴趣的:(APM相关)