【first_try】ardupilot自定义飞行模式


固件版本:ardupilot Plane4.1
仿照 mode_circle 更改代码,增加 mode_Avoid_test 模式。在下面的文件中做相应的修改

mode.h

  1. mode.h中定义新模式 AVOID_TEST 数值为26
AVOID_TEST    = 26,//56行
  1. 仿照ModeCircle创建ModeAvoidTest类,修改mode_number(),name(),name4()
 class ModeAvoidTest: public Mode//722行
{
public:

    Number mode_number() const override { return Number::AVOID_TEST; }
    const char *name() const override { return "AVOIDT"; }
    const char *name4() const override { return "AVOT"; }

    // methods that affect movement of the vehicle in this mode
    void update() override;

    bool does_auto_navigation() const override { return true; }

    bool does_auto_throttle() const override { return true; }

protected:

    bool _enter() override;
};

Plane.h

  1. 添加 friend class ModeAvoidTest
friend class ModeAvoidTest;//143行
  1. 创建 ModeAvoidTest mode_avoid_test;
ModeAvoidTest mode_avoid_test;//263行

mode_avoid_test.cpp

创建 mode_avoid_test.cpp 文件,将 mode_circle.cpp 中内容复制,更改类名为 ModeAvoidTest

#include "mode.h"
#include "Plane.h"

bool ModeAvoidTest::_enter()
{
    // the altitude to circle at is taken from the current altitude
    plane.next_WP_loc.alt = plane.current_loc.alt;

    return true;
}

void ModeAvoidTest::update()
{
    // we have no GPS installed and have lost radio contact
    // or we just want to fly around in a gentle circle w/o GPS,
    // holding altitude at the altitude we set when we
    // switched into the mode
    plane.nav_roll_cd  = plane.roll_limit_cd / 3;
    plane.update_load_factor();
    plane.calc_nav_pitch();
    plane.calc_throttle();
}

events.cpp control_modes.cpp GCS_Mavlink.cpp GCS_Plane.cpp

增加 case Mode::Number::AVOID_TEST: 在switch中,
否则会报错 enumeration value ‘AVOID_TEST’ not handled in switch

case Mode::Number::AVOID_TEST://events.cpp 167行    GCS_Mavlink.cpp  57行   GCS_Plane.cpp  70行

control_modes.cpp中添加 case Mode::Number::AVOID_TEST: ret = &mode_avoid_test;

    case Mode::Number::AVOID_TEST://50行
        ret = &mode_avoid_test;
        break;
    **最终成功!!!**
  • 1
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值