APM/PX4/betaflight/inav开源飞控之IMU方向

news/2024/7/10 19:59:27 标签: 开源, Ardupilot, betaflight

APM/PX4/betaflight/inav开源飞控之IMU方向

1. 源由

飞控硬件厂商在设计飞控的时候,在开发、测试阶段已经将IMU方向配置在硬件定义文件中了。

目前,相对来说,国内比较主流的飞控代码可以分为两大类:

两者坐标系有差别,尤其在硬件配置文件中定义的角度,更是出现非常离奇的情况。这里做一个整体应用级别的分析,希望能够帮助后续定位底层差异。

2. 坐标系

2.1 APM/PX4:机体坐标 + 右手系规则

在这里插入图片描述

betaflightinavxEastyNorthzUp__yaw___20">2.2 betaflight/inav:xEast-yNorth-zUp + yaw反向 + 右手系规则

在这里插入图片描述

3. 转向定义

3.1 APM/PX4

enum Rotation : uint8_t {
    ROTATION_NONE                = 0,
    ROTATION_YAW_45              = 1,
    ROTATION_YAW_90              = 2,
    ROTATION_YAW_135             = 3,
    ROTATION_YAW_180             = 4,
    ROTATION_YAW_225             = 5,
    ROTATION_YAW_270             = 6,
    ROTATION_YAW_315             = 7,
    ROTATION_ROLL_180            = 8,
    ROTATION_ROLL_180_YAW_45     = 9,
    ROTATION_ROLL_180_YAW_90     = 10,
    ROTATION_ROLL_180_YAW_135    = 11,
    ROTATION_PITCH_180           = 12,
    ROTATION_ROLL_180_YAW_225    = 13,
    ROTATION_ROLL_180_YAW_270    = 14,
    ROTATION_ROLL_180_YAW_315    = 15,
    ROTATION_ROLL_90             = 16,
    ROTATION_ROLL_90_YAW_45      = 17,
    ROTATION_ROLL_90_YAW_90      = 18,
    ROTATION_ROLL_90_YAW_135     = 19,
    ROTATION_ROLL_270            = 20,
    ROTATION_ROLL_270_YAW_45     = 21,
    ROTATION_ROLL_270_YAW_90     = 22,
    ROTATION_ROLL_270_YAW_135    = 23,
    ROTATION_PITCH_90            = 24,
    ROTATION_PITCH_270           = 25,
    ROTATION_PITCH_180_YAW_90    = 26, // same as ROTATION_ROLL_180_YAW_270
    ROTATION_PITCH_180_YAW_270   = 27, // same as ROTATION_ROLL_180_YAW_90
    ROTATION_ROLL_90_PITCH_90    = 28,
    ROTATION_ROLL_180_PITCH_90   = 29,
    ROTATION_ROLL_270_PITCH_90   = 30,
    ROTATION_ROLL_90_PITCH_180   = 31,
    ROTATION_ROLL_270_PITCH_180  = 32,
    ROTATION_ROLL_90_PITCH_270   = 33,
    ROTATION_ROLL_180_PITCH_270  = 34,
    ROTATION_ROLL_270_PITCH_270  = 35,
    ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
    ROTATION_ROLL_90_YAW_270     = 37,
    ROTATION_ROLL_90_PITCH_68_YAW_293 = 38, // this is actually, roll 90, pitch 68.8, yaw 293.3
    ROTATION_PITCH_315           = 39,
    ROTATION_ROLL_90_PITCH_315   = 40,
    ROTATION_PITCH_7             = 41,
    ROTATION_ROLL_45             = 42,
    ROTATION_ROLL_315            = 43,
    ///
    // Do not add more rotations without checking that there is not a conflict
    // with the MAVLink spec. MAV_SENSOR_ORIENTATION is expected to match our
    // list of rotations here. If a new rotation is added it needs to be added
    // to the MAVLink messages as well.
    ///
    ROTATION_MAX,
    ROTATION_CUSTOM_OLD          = 100,
    ROTATION_CUSTOM_1            = 101,
    ROTATION_CUSTOM_2            = 102,
    ROTATION_CUSTOM_END,
};

betaflightinav_87">3.2 betaflight/inav

typedef enum {
    ALIGN_DEFAULT = 0, // driver-provided alignment

    // the order of these 8 values also correlate to corresponding code in ALIGNMENT_TO_BITMASK.

                            // R, P, Y
    CW0_DEG = 1,            // 00,00,00
    CW90_DEG = 2,           // 00,00,01
    CW180_DEG = 3,          // 00,00,10
    CW270_DEG = 4,          // 00,00,11
    CW0_DEG_FLIP = 5,       // 00,10,00 // _FLIP = 2x90 degree PITCH rotations
    CW90_DEG_FLIP = 6,      // 00,10,01
    CW180_DEG_FLIP = 7,     // 00,10,10
    CW270_DEG_FLIP = 8,     // 00,10,11

    ALIGN_CUSTOM = 9,    // arbitrary sensor angles, e.g. for external sensors
} sensor_align_e;

4. 实例

注:始终采用Y轴方向朝前进行变换。相关映射,后续会补充,其主要原因,会随着底层分析深入,给出答案!

4.1 I C M 42688 P ICM42688P ICM42688P

正常旋转获得结果,XYZ轴重叠。

  • APM/PX4:ROTATION_ROLL_180_YAW_90
  • betaflight/inav:CW90_DEG

在这里插入图片描述

4.2 M P U 600 0 ∗ MPU6000^* MPU6000

非正常旋转,Y变成X、X变成Y、Z反向,需要驱动底层代码配合,以保持物理方向与应用的一致性。

在这里插入图片描述

5. 参考资料

【1】BetaFlight深入传感设计之九:传感坐标系/机体坐标系/导航坐标系/经纬度坐标系
【2】BetaFlight深入传感设计之八:坐标系
【3】BetaFlight深入传感设计之五:MahonyAHRS & 方向余弦矩阵理论
【4】PX4-Flight Controller/Sensor Orientation
【5】betaflight-Flight-Controller-Orientation
【6】GeoGebra - 数学教学软件

6. 补充资料-常见bf-apm映射

# betaflight sensor alignment is a mysterious art
# some of these might be right but you should always check
alignment = {
    "CW0" : "ROTATION_YAW_270",
    "CW90" : "ROTATION_NONE",
    "CW180" : "ROTATION_YAW_90",
    "CW270" : "ROTATION_YAW_180",
    "CW0FLIP" : "ROTATION_ROLL_180_YAW_270",
    "CW90FLIP" : "ROTATION_ROLL_180",
    "CW180FLIP" : "ROTATION_ROLL_180_YAW_90",
    "CW270FLIP" : "ROTATION_PITCH_180",
    "DEFAULT" : "ROTATION_NONE",
}

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

相关文章

【读点论文】FMViT: A multiple-frequency mixing Vision Transformer-期待源码

FMViT: A multiple-frequency mixing Vision Transformer Abstract transformer模型近年来在计算机视觉任务中得到了广泛的应用。然而,由于自关注的时间和内存复杂度是二次的,并且与输入token的数量成正比,大多数现有的(Vision transformer,…

【MATLAB源码-第80期】基于蚯蚓优化算法(EOA)的无人机三维路径规划,输出做短路径图和适应度曲线

操作环境: MATLAB 2022a 1、算法描述 蚯蚓优化算法(Earthworm Optimisation Algorithm, EOA)是一种启发式算法,灵感来源于蚯蚓在自然界中的行为模式。蚯蚓优化算法主要模仿了蚯蚓在寻找食物和逃避天敌时的行为策略。以下是蚯蚓…

java常见集合遍历的空指针情况

1.请看以下代码 int[] arr new int[0]; // 空数组 try { for (int i : arr) { System.out.println(i); } } catch (Exception e) { e.printStackTrace(); } 如果数组为空,循环体不会执行,因此不会抛出空指针异常。这是因为foreach循环在遍历数…

第14届蓝桥杯青少组python试题解析:22年10月选拔赛

选择题 T1. 执行print (5%3) 语句后,输出的结果是 ( ) 0 1 2 3 T2. 以下选项中,哪一个是乘法运算符?() % // * ** T3. 已知x3,求x//2x**2的运算结果? 7.5 10 8 10.5 T4. 以下选项中,对下面程序的打印…

Django测试环境搭建及ORM查询(创建外键|跨表查询|双下划线查询 )

文章目录 一、表查询数据准备及测试环境搭建模型层前期准备测试环境搭建代码演示 二、ORM操作相关方法三、ORM常见的查询关键字四、ORM底层SQL语句五、双下划线查询数据查询(双下划线)双下划线小训练Django ORM __双下划线细解 六、ORM外键字段创建基础表…

【VSCode】Visual Studio Code 下载与安装教程

前言 Visual Studio Code(简称 VS Code)是一个轻量级的代码编辑器,适用于多种编程语言和开发环境。本文将介绍如何下载和安装 Visual Studio Code。 下载安装包 首先,我们需要从官方网站下载 Visual Studio Code 的安装包。请访…

【Java 进阶篇】JQuery 遍历 —— `each()` 方法的奇妙之旅

在前端的世界里,操作元素是我们开发者最为频繁的任务之一。为了更好地操控页面上的元素,JQuery 提供了许多强大的工具,其中 each() 方法是一颗璀璨的明星。本文将深入探讨 each() 方法的原理和用法,带你踏上一场遍历之旅。 起步&…

C++: 模板初阶

文章目录 一. 泛型编程二. 函数模板函数模板的原理函数模板的实例化隐式实例化: 让编译器根据实参推演模板参数的实际类型显示实例化: 在函数名后的<>中制定模板参数的世纪类型 模板参数的匹配原则 三. 类模板类模板的定义格式类模板的实例化 一. 泛型编程 如何实现一个…