向Ardupilot中添加新的飞行模式(以ArduSub为例)

本次以ArduSub为例介绍如何向APM固件中添加新的飞行模式以方便后续开发,其他车辆类型操作相似,本篇也可用作参考。

参考资料:

Adding a New Flight Mode

Creating newflight mode in Ardusub


首先在ardupilot/ArduSub/文件路径下,新建一个用于添加新的飞行模式的文件control_newMode.cpp。然后,向内部添加代码如下:

#include "Sub.h"

bool Sub::newmode_init()
{
    
    
	return true;
}

void Sub::newmode_init()
{
    
    

}

保存退出之后,进入ardupilot/libraries/AP_JSButton/AP_JSBottton.h,找到k_mode_xxx形式的模式定义如下:

        k_mode_manual           = 5,            ///< enter enter manual mode
        k_mode_stabilize        = 6,            ///< enter stabilize mode
        k_mode_depth_hold       = 7,            ///< enter depth hold mode
        k_mode_poshold          = 8,            ///< enter poshold mode
        k_mode_auto             = 9,            ///< enter auto mode
        k_mode_circle           = 10,           ///< enter circle mode
        k_mode_guided           = 11,           ///< enter guided mode
        k_mode_acro             = 12,           ///< enter acro mode
        k_mode_newmode			= 13,			///...

在最后添加你的新模式,我这里选择的数字为13(只要不超过后面参数的值21即可)。然后添加你对应的备注。

回到ardupilot/ArduSub/defines.h文件中,找到control_mode_t枚举类型定义,在最后面添加你的新模式,并添加备注描述

// Auto Pilot Modes enumeration
enum control_mode_t {
    
    
    STABILIZE =     0,  // manual angle with manual depth/throttle
    ACRO =          1,  // manual body-frame angular rate with manual depth/throttle
    ALT_HOLD =      2,  // manual angle with automatic depth/throttle
    AUTO =          3,  // fully automatic waypoint control using mission commands
    GUIDED =        4,  // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
    CIRCLE =        7,  // automatic circular flight with automatic throttle
    SURFACE =       9,  // automatically return to surface, pilot maintains horizontal control
    POSHOLD =      16,  // automatic position hold with manual override, with automatic throttle
    MANUAL =       19,  // Pass-through input with no stabilization
    MOTOR_DETECT = 20,  // Automatically detect motors orientation
	NEWMODE =	   21	// ...
};

再进入ardupilot/ArduSub/Sub.h,向内部添加代码段如下(理论上是可以在任意位置,但是最好添加在别的飞行模式的旁边)

bool newmode_init(void);
void newmode_run();

然后在ardupilot/ArduSub/flight_mode.cpp中,对set_mode()和update_flight_mode()方法进行修改,具体就是在switch函数下面添加对应的case情况函数。

// 在set_mode()方法中
    case NEWMODE:
    	success = newmode_init();
    	break;
...
///在update_flight_mode()方法中
    case NEWMODE:
    	success = newmode_run();
    	break;

最后,在ardupilot/ArduSub/joystick.cpp中,找到

void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)

在其中的switch-case语句中的default前添加

    case JSButton::button_function_t::k_mode_newmode:
    	set_mode(NEWMODE, MODE_REASON_TX_COMMAND);

然后保存退出即可。


编译

cd ardupilot/
rm -rf build/
./waf configure --board Pixhawk1
./waf sub

编译成功!

在这里插入图片描述
后续工作是如何使QGC能够识别出新的飞行模式,目前尚在研究中。也可考虑使用mavros或者pymavlink进行后续的开发作业。目前先研究到这~

猜你喜欢

转载自blog.csdn.net/moumde/article/details/109075369