ArduPilot开源飞控之AP_InertialNav

news/2024/7/10 19:45:04 标签: 开源, Ardupilot

ArduPilot开源飞控之AP_InertialNav

  • 1. 源由
  • 2. 调用关系
  • 3. 重要例程
    • 3.1 read_inertia
    • 3.2 update
  • 4. 封装接口
    • 4.1 get_filter_status
    • 4.2 get_position_neu_cm
    • 4.3 get_position_xy_cm
    • 4.4 get_position_z_up_cm
    • 4.5 get_velocity_neu_cms
    • 4.6 get_velocity_xy_cms
    • 4.7 get_speed_xy_cms
    • 4.8 get_velocity_z_up_cms
  • 5. 参考资料

1. 源由

AP_InternationalNav类是NavEKF的封装,提供关于导航相关的信息:

  1. 坐标位置
  2. 相对位置
  3. 运动速度
  4. 导航状态

2. 调用关系

状态更新函数调用嵌套关系。

FAST_TASK(read_inertia)
 └──> Copter::read_inertia
     └──> AP_InertialNav::update

3. 重要例程

3.1 read_inertia

  1. current_loc.lat
  2. current_loc.lng
  3. current_loc.alt
Copter::read_inertia
 │
 │  // inertial altitude estimates. Use barometer climb rate during high vibrations
 ├──> inertial_nav.update(vibration_check.high_vibes);
 │
 │  // pull position from ahrs
 ├──> Location loc;
 ├──> ahrs.get_location(loc);
 ├──> current_loc.lat = loc.lat;
 ├──> current_loc.lng = loc.lng;
 │
 │  // exit immediately if we do not have an altitude estimate
 ├──> <!inertial_nav.get_filter_status().flags.vert_pos>
 │   └──> return;
 │
 │  // current_loc.alt is alt-above-home, converted from inertial nav's alt-above-ekf-origin
 ├──> const int32_t alt_above_origin_cm = inertial_nav.get_position_z_up_cm();
 ├──> current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_ORIGIN);
 └──> <!ahrs.home_is_set() || !current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)>
     │  // if home has not been set yet we treat alt-above-origin as alt-above-home
     └──> current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_HOME);

3.2 update

  1. _relpos_cm
  2. _velocity_cm
AP_InertialNav::update
 │
 │  // get the NE position relative to the local earth frame origin
 ├──> Vector2f posNE;
 ├──> <_ahrs_ekf.get_relative_position_NE_origin(posNE)>
 │   ├──> _relpos_cm.x = posNE.x * 100; // convert from m to cm
 │   └──> _relpos_cm.y = posNE.y * 100; // convert from m to cm
 │
 │  // get the D position relative to the local earth frame origin
 ├──> float posD;
 ├──> <_ahrs_ekf.get_relative_position_D_origin(posD)>
 │   └──> _relpos_cm.z = - posD * 100; // convert from m in NED to cm in NEU
 │
 │  // get the velocity relative to the local earth frame
 ├──> Vector3f velNED;
 └──> <_ahrs_ekf.get_velocity_NED(velNED)>
     │  // during high vibration events use vertical position change
     ├──> <high_vibes>
     │   ├──> float rate_z;
     │   └──> <_ahrs_ekf.get_vert_pos_rate_D(rate_z)>
     │       └──> velNED.z = rate_z;
     ├──> _velocity_cm = velNED * 100; // convert to cm/s
     └──> _velocity_cm.z = -_velocity_cm.z; // convert from NED to NEU

4. 封装接口

4.1 get_filter_status

/**
 * get_filter_status : returns filter status as a series of flags
 */
nav_filter_status AP_InertialNav::get_filter_status() const
{
    nav_filter_status status;
    _ahrs_ekf.get_filter_status(status);
    return status;
}

union nav_filter_status {
    struct {
        bool attitude           : 1; // 0 - true if attitude estimate is valid
        bool horiz_vel          : 1; // 1 - true if horizontal velocity estimate is valid
        bool vert_vel           : 1; // 2 - true if the vertical velocity estimate is valid
        bool horiz_pos_rel      : 1; // 3 - true if the relative horizontal position estimate is valid
        bool horiz_pos_abs      : 1; // 4 - true if the absolute horizontal position estimate is valid
        bool vert_pos           : 1; // 5 - true if the vertical position estimate is valid
        bool terrain_alt        : 1; // 6 - true if the terrain height estimate is valid
        bool const_pos_mode     : 1; // 7 - true if we are in const position mode
        bool pred_horiz_pos_rel : 1; // 8 - true if filter expects it can produce a good relative horizontal position estimate - used before takeoff
        bool pred_horiz_pos_abs : 1; // 9 - true if filter expects it can produce a good absolute horizontal position estimate - used before takeoff
        bool takeoff_detected   : 1; // 10 - true if optical flow takeoff has been detected
        bool takeoff            : 1; // 11 - true if filter is compensating for baro errors during takeoff
        bool touchdown          : 1; // 12 - true if filter is compensating for baro errors during touchdown
        bool using_gps          : 1; // 13 - true if we are using GPS position
        bool gps_glitching      : 1; // 14 - true if GPS glitching is affecting navigation accuracy
        bool gps_quality_good   : 1; // 15 - true if we can use GPS for navigation
        bool initalized         : 1; // 16 - true if the EKF has ever been healthy
        bool rejecting_airspeed : 1; // 17 - true if we are rejecting airspeed data
        bool dead_reckoning     : 1; // 18 - true if we are dead reckoning (e.g. no position or velocity source)
    } flags;
    uint32_t value;
};

4.2 get_position_neu_cm

/**
 * get_position_neu_cm - returns the current position relative to the EKF origin in cm.
 *
 * @return
 */
const Vector3f &AP_InertialNav::get_position_neu_cm(void) const 
{
    return _relpos_cm;
}

4.3 get_position_xy_cm

/**
 * get_position_xy_cm - returns the current x-y position relative to the EKF origin in cm.
 *
 * @return
 */
const Vector2f &AP_InertialNav::get_position_xy_cm() const
{
    return _relpos_cm.xy();
}

4.4 get_position_z_up_cm

/**
 * get_position_z_up_cm - returns the current z position relative to the EKF origin, frame z-axis up, in cm.
 * @return
 */
float AP_InertialNav::get_position_z_up_cm() const
{
    return _relpos_cm.z;
}

4.5 get_velocity_neu_cms

/**
 * get_velocity_neu_cms - returns the current velocity in cm/s
 *
 * @return velocity vector:
 *      		.x : latitude  velocity in cm/s
 * 				.y : longitude velocity in cm/s
 * 				.z : vertical  velocity in cm/s
 */
const Vector3f &AP_InertialNav::get_velocity_neu_cms() const
{
    return _velocity_cm;
}

4.6 get_velocity_xy_cms

/**
 * get_velocity_xy_cms - returns the current x-y velocity relative to the EKF origin in cm.
 *
 * @return
 */
const Vector2f &AP_InertialNav::get_velocity_xy_cms() const
{
    return _velocity_cm.xy();
}

4.7 get_speed_xy_cms

/**
 * get_speed_xy_cms - returns the current horizontal speed in cm/s
 *
 * @returns the current horizontal speed in cm/s
 */
float AP_InertialNav::get_speed_xy_cms() const
{
    return _velocity_cm.xy().length();
}

4.8 get_velocity_z_up_cms

/**
 * get_velocity_z_up_cms - returns the current z-axis velocity, frame z-axis up, in cm/s
 *
 * @return z-axis velocity, frame z-axis up, in cm/s
 */
float AP_InertialNav::get_velocity_z_up_cms() const
{
    return _velocity_cm.z;
}

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计


http://www.niftyadmin.cn/n/5089314.html

相关文章

DocCMS keyword SQL注入

漏洞描述 DocCMS keyword参数存在 SQL注入漏洞&#xff0c;攻击者通过漏洞可以获取数据库信息 漏洞复现 访问url&#xff1a; 漏洞证明&#xff1a; 文笔生疏&#xff0c;措辞浅薄&#xff0c;望各位大佬不吝赐教&#xff0c;万分感谢。 免责声明&#xff1a;由于传播或利…

刚体动力学-牛顿欧拉方程(刚体旋转)

Newton-Euler方程用来描述刚体的运动&#xff1a; 欧拉第一定律 刚体的线动量 p \mathbf p p的变化率等于所有外力的合数 F e x t F_{\mathrm{ext}} Fext​作用于刚体&#xff1a; F e x t d p d t \mathbf F_{\mathrm{ext}}\frac{d \mathbf{p}}{d t} Fext​dtdp​ 构成刚体…

项目经理长期工作是什么

1、 为项目团队提供培训指导&#xff0c;传授项目管理知识与技能 2、 收集项目案例和经验教训&#xff0c;建立项目知识库 3、 根据项目数据&#xff0c;持续优化和改进项目流程 4、 维护客户关系&#xff0c;洞悉客户需求&#xff0c;提升客户满意度 5、 进行职业发展…

【牛客网刷题(数据结构)】:环形链表的约瑟夫问题

描述 编号为 1 到 n 的 n 个人围成一圈。从编号为 1 的人开始报数&#xff0c;报到 m 的人离开。 下一个人继续从 1 开始报数。 n-1 轮结束以后&#xff0c;只剩下一个人&#xff0c;问最后留下的这个人编号是多少&#xff1f; O(n) 示例1 好环形链表的约瑟夫问题是一个经典的问…

ODrive移植keil(七)—— 插值算法和偏置校准

目录 一、角度读取1.1、硬件接线1.2、程序演示1.3、代码说明 二、锁相环和插值算法2.1、锁相环2.2、插值2.3、角度补偿 三、偏置校准3.1、硬件接线3.2、官方代码操作3.3、移植后的代码操作3.4、代码说明3.5、SimpleFOC的偏置校准对比 ODrive、VESC和SimpleFOC 教程链接汇总&…

cmd/bat 输出符,控制台日志输出到文件

前言 略 输出符 A > B将A执行结果覆盖写入B A >> B将A执行结果追加写入B 常用句柄 句柄句柄的数字代号描述STDIN0键盘输入STDOUT1输出到命令提示符窗口STDERR2错误输出到命令提示符窗口 控制台日志输出到文件 1.bat 1>d:\log.log将控制台日志输出到文件 d:…

mysql数据库 windows迁移至linux

1.打开navicat&#xff0c;选择一个数据库进行操作&#xff1a; 之后文件会保存为一个xxx.sql文件&#xff0c;之后打开xftp&#xff0c;把生成的sql放进一个文件夹中(/home/dell/linuxmysql)&#xff1a; 之后登录mysql数据库&#xff0c;并创建一个新的数据库&#xff0c;然后…

8位端口检测8位独立按键

/*----------------------------------------------- 内容&#xff1a;如计算器输入数据形式相同 从左往右 利用整个端口扫描读取按键值 ------------------------------------------------*/ #include<reg52.h> //包含头文件&#xff0c;一般情况不需要改动&#xff0c;…