Ardupilot四元数姿态控制函数attitude_controller_run_quat解析

2023-05-16

Ardupilot四元数姿态控制函数attitude_controller_run_quat解析

  • 源码解析
  • 细节讲解
    • thrust_heading_rotation_angles()
    • update_ang_vel_target_from_att_error()
    • 角度前馈量旋转解释
  • 姿态更新部分

在开始阅读本文之前,建议可以先看一下前面几篇博文,当然你基础好直接看也是没事的~
详解APM的开方控制器sqrt_controller
Ardupilot倾转分离函数thrust_heading_rotation_angles
Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析

 

源码解析

以n系简称NED坐标系,b系简称机体坐标系,tb表示期望姿态,cb表示当前姿态。

// 根据姿态误差计算得出期望角速率
void AC_AttitudeControl::attitude_controller_run_quat()
{
	// 检索四元数车辆姿态
	// 获取到当前姿态的四元数并保存到attitude_vehicle_quat
    Quaternion attitude_vehicle_quat;
    _ahrs.get_quat_body_to_ned(attitude_vehicle_quat);

	// 计算姿态误差
	// _attitude_target_quat:输入参数,在n系下期望姿态的四元数,旋转方向tb->n
	// attitude_vehicle_quat:输入参数,在n系下当前姿态的四元数,旋转方向cb->n
	// attitude_error_vector:传入传出参数,姿态误差向量
	// _thrust_error_angle:传入传出参数,期望z轴和当前z轴的误差(详见轴角分离),即推力方向上的偏差角
	// 该函数通过前两个输入的四元数参数计算得到各轴的姿态偏差
	// 经过此函数后得到的参数均在b系下
    Vector3f attitude_error_vector;
    thrust_heading_rotation_angles(_attitude_target_quat, attitude_vehicle_quat, attitude_error_vector, _thrust_error_angle);

	// P控制器,输入为姿态误差,输出为期望角速率
	// 函数内部根据是否开启了sqrt_controller来区分计算各通道的期望角速率_rate_target_ang_vel
	// 是,则使用开方调整过的P控制器
	// 否,则使用常规的Kp*error
    _rate_target_ang_vel = update_ang_vel_target_from_att_error(attitude_error_vector);

	// 对P控制器输出叠加前馈项,尝试确保侧倾和俯仰误差随车身框架而不是参考框架旋转
	// x轴的前馈项 = y轴的姿态误差(限幅后的)*陀螺仪获取的z轴角速度
	// y轴的前馈项 = x轴的姿态误差(限幅后的)*陀螺仪获取的z轴角速度
	// 注意此处并没有对z轴的期望角速率进行处理
    // todo: this should probably be a matrix that couples yaw as well.
    _rate_target_ang_vel.x += constrain_float(attitude_error_vector.y, -M_PI / 4, M_PI / 4) * _ahrs.get_gyro().z;
    _rate_target_ang_vel.y += -constrain_float(attitude_error_vector.x, -M_PI / 4, M_PI / 4) * _ahrs.get_gyro().z;

	// 期望角速率限幅
    ang_vel_limit(_rate_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));

	// 角速度前馈旋转到机体坐标中(对该处有疑问的详见本文后面)
	// _attitude_target_ang_vel是一个全局变量,表示期望姿态的期望角速率,是由input_euler_angle_roll_pitch_yaw等类似函数获取到的前馈速率
	// attitude_target_ang_vel_quat在此处表明是一个向量[0,v]
	Quaternion attitude_target_ang_vel_quat = Quaternion(0.0f, _attitude_target_ang_vel.x, _attitude_target_ang_vel.y, _attitude_target_ang_vel.z);
	// 运算过程注意四元数和旋转矩阵一样是可以上下标相互约去的,此处以Q(a)(b)形式表明上标为a,下标为b,表示b向a的旋转过程
	// attitude_vehicle_quat前面说过是表示cb->n旋转的单位四元数,求逆后表示n->cb
	// to_to_from_quat = Q(cb)(n)*Q(n)(tb)=Q(cb)(tb)
	// 表明获取的四元数to_to_from_quat表示tb->cb的旋转,计算公式也可视作期望姿态与当前姿态的作差
	Quaternion to_to_from_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
	// 将tb下的期望角速率旋转至cb下获取当前姿态的角速率期望前馈叠加量desired_ang_vel_quat
    Quaternion desired_ang_vel_quat = to_to_from_quat.inverse() * attitude_target_ang_vel_quat * to_to_from_quat;

	// 校正推力矢量并平稳添加前馈和偏航输入
	// 下述过程根据推力角误差大小分配在Z轴YAW角上的数学计算结果和传感器测量值之间的确信度来确定Z轴的期望角速度
	// 同时将前馈控制量添加到各轴
	// 当推力角误差特别大的时候,表明计算出来的期望值不可信,此时z轴期望角速度取陀螺仪测量值
    if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {
        _rate_target_ang_vel.z = _ahrs.get_gyro().z;
	} else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
		// 当推力角误差较大时,根据之前计算出来的推力角误差_thrust_error_angle计算出前馈因子
		// 对各轴的旋转角速度各自叠加前馈控制量
        float feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);
        _rate_target_ang_vel.x += desired_ang_vel_quat.q2 * feedforward_scalar;
        _rate_target_ang_vel.y += desired_ang_vel_quat.q3 * feedforward_scalar;
        _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
		// 校正推力矢量,feedforward_scalar表示对计算出的数学结果的确信度,(1- feedforward_scalar)则表示对陀螺仪测得的角速度的确信度
		// 两者综合得到最后的期望角速率
        _rate_target_ang_vel.z = _ahrs.get_gyro().z * (1.0 - feedforward_scalar) + _rate_target_ang_vel.z * feedforward_scalar;
	} else {
		// 推力角误差较小时,表明当前数学计算得到的期望角速率可信度较高,直接进行前馈叠加
        _rate_target_ang_vel.x += desired_ang_vel_quat.q2;
        _rate_target_ang_vel.y += desired_ang_vel_quat.q3;
        _rate_target_ang_vel.z += desired_ang_vel_quat.q4;
    }

    if (_rate_bf_ff_enabled) {
        // 当开启机体速率前馈时,实时计算更新期望姿态四元数,每一次更新都需要将其单位化
        Quaternion attitude_target_update_quat;
        attitude_target_update_quat.from_axis_angle(Vector3f(_attitude_target_ang_vel.x * _dt, _attitude_target_ang_vel.y * _dt, _attitude_target_ang_vel.z * _dt));
        _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
        _attitude_target_quat.normalize();
    }

    // 确保四元数已经被单位化
    _attitude_target_quat.normalize();

	// 记录姿态误差以处理EKF重置
	// 等式相当于将_attitude_target_quat表示的期望姿态减去attitude_vehicle_quat表示的当前姿态
    _attitude_ang_error = attitude_vehicle_quat.inverse() * _attitude_target_quat;
}

总结:attitude_controller_run_quat()函数在内部通过调用thrust_heading_rotation_angles()函数计算出姿态误差,然后根据姿态误差调用了P控制器得到期望角速率,并进行了前馈叠加及平滑操作。

 

细节讲解

thrust_heading_rotation_angles()

这个函数主要的作用就是根据输入的期望姿态和当前姿态计算出姿态误差,详细介绍请看我之前的博文:Ardupilot倾转分离函数thrust_heading_rotation_angles

update_ang_vel_target_from_att_error()

这个函数内部代码比较简单,但是还是说一下。

主要就是P控制器的作用,将输入的姿态误差处理之后转换为期望角速率输出。

可以很清楚看到内部会根据是否启用_use_sqrt_controller来进行不同的处理,如果_use_sqrt_controller = 1,那么会调用整定后的P控制器sqrt_controller进行计算;而如果_use_sqrt_controller = 0,那么就会按照传统计算方式 Kp*error 进行计算。

关于sqrt_controller详见:详解APM的开方控制器sqrt_controller

// Update rate_target_ang_vel using attitude_error_rot_vec_rad
Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)
{
    Vector3f rate_target_ang_vel;
    // Compute the roll angular velocity demand from the roll angle error
    if (_use_sqrt_controller) {
        rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, _p_angle_roll.kP(), constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
    } else {
        rate_target_ang_vel.x = _p_angle_roll.kP() * attitude_error_rot_vec_rad.x;
    }
    // todo: Add Angular Velocity Limit

    // Compute the pitch angular velocity demand from the pitch angle error
    if (_use_sqrt_controller) {
        rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, _p_angle_pitch.kP(), constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt);
    } else {
        rate_target_ang_vel.y = _p_angle_pitch.kP() * attitude_error_rot_vec_rad.y;
    }
    // todo: Add Angular Velocity Limit

    // Compute the yaw angular velocity demand from the yaw angle error
    if (_use_sqrt_controller) {
        rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, _p_angle_yaw.kP(), constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt);
    } else {
        rate_target_ang_vel.z = _p_angle_yaw.kP() * attitude_error_rot_vec_rad.z;
    }
    // todo: Add Angular Velocity Limit
    return rate_target_ang_vel;
}

角度前馈量旋转解释

有人可能会对这段代码的旋转过程有所疑惑,然而实际上在我上一篇博文(Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析)已经对这个问题进行了解释,这边再细说一下。

	// 角速度前馈旋转到机体坐标中(对该处有疑问的详见本文后面)
	// _attitude_target_ang_vel是一个全局变量,表示期望姿态的期望角速率,是由input_euler_angle_roll_pitch_yaw等类似函数获取到的前馈速率
	// attitude_target_ang_vel_quat在此处表明是一个向量[0,v]
	Quaternion attitude_target_ang_vel_quat = Quaternion(0.0f, _attitude_target_ang_vel.x, _attitude_target_ang_vel.y, _attitude_target_ang_vel.z);
	// 运算过程注意四元数和旋转矩阵一样是可以上下标相互约去的,此处以Q(a)(b)形式表明上标为a,下标为b,表示b向a的旋转过程
	// attitude_vehicle_quat前面说过是表示cb->n旋转的单位四元数,求逆后表示n->cb
	// to_to_from_quat = Q(cb)(n)*Q(n)(tb)=Q(cb)(tb)
	// 表明获取的四元数to_to_from_quat表示tb->cb的旋转,计算公式也可视作期望姿态与当前姿态的作差
	Quaternion to_to_from_quat = attitude_vehicle_quat.inverse() * _attitude_target_quat;
	// 将tb下的期望角速率旋转至cb下获取当前姿态的角速率期望前馈叠加量desired_ang_vel_quat
    Quaternion desired_ang_vel_quat = to_to_from_quat.inverse() * attitude_target_ang_vel_quat * to_to_from_quat;

可以看到这段代码将前馈期望速度从期望姿态转换到了当前姿态下,那么问题就是,为什么这个期望速度是在期望姿态下而不是原本就在当前姿态的呢?

因为在之前的input_euler_angle_roll_pitch_yaw()函数(其他类似)中,通过对本次输入的期望姿态和自驾仪中当前保存的未更新前的期望姿态作差求出姿态误差,然后再得到了_attitude_target_ang_vel这个期望角速率。

而在现在我们这个函数中,我们是通过期望姿态与当前姿态作差得到的姿态误差来求取期望角速率_rate_target_ang_vel。

因此_attitude_target_ang_vel是在期望姿态tb下的期望角速率,而_rate_target_ang_vel则是在当前姿态cb下的期望角速率,叠加前需要将_attitude_target_ang_vel从tb转换到cb下。

姿态更新部分

    if (_rate_bf_ff_enabled) {
        // 当开启机体速率前馈时,实时计算更新期望姿态四元数,每一次更新都需要将其单位化
        Quaternion attitude_target_update_quat;
        attitude_target_update_quat.from_axis_angle(Vector3f(_attitude_target_ang_vel.x * _dt, _attitude_target_ang_vel.y * _dt, _attitude_target_ang_vel.z * _dt));
        _attitude_target_quat = _attitude_target_quat * attitude_target_update_quat;
        _attitude_target_quat.normalize();
    }

该部分仍然跟之前讲解的input_euler_angle_roll_pitch_yaw()及类似函数有关,在input_euler_angle_roll_pitch_yaw()中如果开启了前馈,那么会计算出前馈速率,但是并没有将本次输入的期望姿态更新到当前保存的期望姿态中;而如果没有开启前馈,则会将本次输入的期望姿态更新到当前期望姿态,然后将前馈速率置0。

因此,此处解决了我们之前说过的如果开启前馈,姿态更新将在attitude_controller_run_quat()中更新的疑惑。

 

参考资料:

如何用四元数表示反向旋转,类似于旋转矩阵的转置表示反向旋转?

[飞控]姿态误差(三)-四元数和轴角求误差

 

如有错误请及时留言告知。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

Ardupilot四元数姿态控制函数attitude_controller_run_quat解析 的相关文章

  • java prometheus 自定义exporter开发,以及实现多个接口返回metrics

    普罗 自定义exporter开发 exporter的作用是采集需要监控的数据 xff0c 并将采集到的数据转换成prometheus所需要的数据格式 xff0c 将这些转换后的数据返回 xff0c 供给prometheus 使用 java
  • 双系统重装Ubuntu经验分享

    真的很喜欢ubuntu 但又没有恒心把它学通透 xff0c 毕竟不是相关专业 第一次重装是因为没多少经验 xff0c 安装qqforlinux的时候多了两个东西 xff0c 还自己生成了快捷方式 xff0c 就想点开看看是啥 xff0c 结
  • 还在迷茫不知Dashboard是什么?答案在文中揭晓

    Dashboard的中文翻译是 仪表盘 xff0c 与汽车的仪表盘相同 一种反映车辆各系统工作状况的装置 xff0c 有车速里程表 转速表 燃油表等 司机可以很方便地从汽车仪表盘中获得汽车整体状况 而Dashboard沿袭了汽车仪表盘理念
  • 问题:UPDATE 失败,因为下列 SET 选项的设置不正确: 'ARITHABORT'。

    解决方案 1 你可以在TSQL前Set ARITHABORT ON 代码如下 Set ARITHABORT ON GO INSERT INTO ta 2 在ADO NET中 你可以这样来写 C 代码 MyConnection Execute
  • 智能制造:三体智能革命

    赵敏 宁振波 郭朝晖是走向智能研究院资深专家 xff0c 三体智能革命 编委会中三位重要作者 他们从去年5月起多次参加了中国工程院主持的 中国智能制造发展战略研究报告 的研讨 评审与修订工作 xff0c 对该报告的形成过程 研究主旨和详细内
  • 小觅相机SDK samples安装Link error: cannot find -lvtkproj4

    Link error cannot find lvtkproj4 error ld returned 1 exit status 找不到相关动态库文件 设置软链接 xff1a ln s usr lib x86 64 linux gnu li
  • 年度回忆录(2011.12----2012.09)

    前几天刚刚参加了提高班十期的开学典礼 xff0c 最近师院的新生也陆 陆续 续的开始报道了 每年到这个时候都会感慨 年年岁岁花相似 xff0c 年年岁岁人不同 啊 对于提高班来说每年都有新的血液注入进来 xff0c 提高班的队伍在不断的扩大
  • python函数(变量,参数)

    函数的变量 1 xff0c 全局变量 定义在最外层的变量 xff0c 对于所有的内函数都能调用 2 xff0c 局部变量 定义在函数内的变量叫做局部变量 xff0c 在函数外是不能访问局部变量 注 xff1a 全局变量不能直接在函数内部进行
  • 程序员读书和练习的方法(个人观点)

    lt 传送门 gt 针对本文的交流探讨 gt 总宗旨 xff1a 打好计算机通用理论基础 通用实战能力 xff0c 便于需要时对各领域的无障碍深钻 时间宝贵 xff0c 不要为了学习而学习 计算机通用理论基础 xff1a 计算机各领域理论基
  • 从零开始的Ubuntu 16.04下PX4编译环境的搭建

    近来入手了一块pixhawk xff0c 想进行一些基于已有代码的二次加工 xff0c 于是到官网https dev px4 io 上看教程 官网上的教程是分为中文 英文以及韩文的版本 很多人肯定第一反应就是看中文的版本 但是这样做弊端真的
  • 驱动程序开发:SPI设备驱动

    目录 Linux下SPI驱动简介SPI架构概述SPI适配器 xff08 控制器 xff09 SPI设备驱动spi driver注册示例SPI 设备和驱动匹配过程编写imc20608六轴传感器SPI驱动设备树编写操作具体的imc20608驱动
  • 操作系统知识点(二)

    文章目录 内存管理程序执行过程内存保护 连续分配非连续分配基本分页存储管理方式基本分段存储管理方式段页式存储管理方式 虚拟内存局部性原理请求分页存储管理 内存管理 内存管理 Memory Management 是操作系统设计中最重要和最复杂
  • VR行业发展的前景和现状?

    标题 VR行业发展的前景和现状 xff1f 1 一个新事物的产生 xff0c 总是伴随着看好和唱衰两种声音 这两种态度自然有其可以理解的地方 xff0c 因为摆在我们面前的是未知 xff0c 而坐在餐桌前的两拨人 xff0c 站在不同的角度
  • 头文件与库的区别

    昨天突然问了一下什么是头文件 xff0c 我一听就傻了 xff0c 虽然上课的时候老师在讲编译的四个过程的时候说了一下 xff0c 但是还是不太理解 xff0c 我们知道编译过程中的预处理阶段会进行头文件展开 xff0c 宏替换以及条件编译
  • 进程、线程

    线程 xff08 thread xff09 线程其实是操作系统能够进行运算调度的最小单位 它是被包含在进程之中的 xff0c 是进程中的实际运作单位 一条线程指的是进程中一个单一顺序的控制流 xff0c 一个进程中可以并发多个线程 xff0
  • 基于Zynq7020双千兆以太网的数字信号处理板设计

    一 背景 背景 Xilinx公司在2010年发布了可扩展的处理器平台Zynq7000系列 xff0c 它采用了28nm工艺 xff0c 将FPGA与ARM cortex A9集成在一颗芯片上 xff0c 实现了高性能 高集成度 低功耗 Zy
  • 深入理解JS中的变量作用域

    在 JS 当中一个变量的作用域 xff08 scope xff09 是程序中定义这个变量的区域 变量分为两类 xff1a 全局 xff08 global xff09 的和局部的 其中全局变量的作用域是全局性的 xff0c 即在 JavaSc
  • 硬件工程师,从零开始无人机开发。

    毕业已经五年了 xff0c 一直在杭州某大厂 xff0c 做无人机硬件开发 无人机这块 xff0c 我进去的时候大厂刚开始 做 xff0c 有幸参与到整个无人机的硬件开发 我这个刚毕业的技术小白 xff0c 在这五年间成长了很多 无奈 今年
  • 个人总结:板球控制系统之串级PID整定方法,速度环与位置环,40S任务10S完成

    其实单环我们先出了所有题目 xff0c 但是效果显然没有串级PID的效果好 xff0c 有人需要的话可以把程序包发出来 xff0c 板球运行视屏也有 另外 xff1a 天下舵机参差不齐 xff08 哪怕型号相同 xff09 xff0c 想要
  • 树莓派3B+踩坑记录:一、安装Ubuntu Mate

    树莓派3B 43 踩坑记录 xff1a 一 安装Ubuntu Mate 树莓派 xff0c Ubuntu xff0c ROS硬件准备软件准备系统烧录安装Ubuntu Mate更换国内源网络配置开启ssh远程其他彩虹屏解决方案XShell和X

随机推荐

  • PointNet代码详解

    PointNet代码详解 最近在做点云深度学习的机器人抓取 xff0c 这篇博客主要是把近期学习PointNet的一些总结的知识点汇总一下 PointNet概述详见以下网址和博客 xff0c 这里也就不再赘述了 三维深度学习之pointne
  • 卡尔曼滤波通俗易懂的解释

    关于卡尔曼滤波 xff0c 网上的资料很多 xff0c 但是有很大一部分都是不断堆叠公式 xff0c 然后用各种晦涩难懂的专业术语进行解释 xff0c 说实话我刚开始看的时候也是云里雾里 xff0c 因此写下这篇博客是为了照顾和我一样的萌新
  • STM32通过PWM控制ESC30C电调

    最近在搞一个水下推进器 xff0c 这东西的控制其实跟四旋翼的螺旋桨控制差不多 但我也是第一次用STM32板子来控制电调驱动桨叶旋转 xff0c 因此踩了很多坑 网上找了很多资料 xff0c 但是很多都写的不是很清楚 xff0c 这边稍微记
  • STM32F7同一定时器多路输出PWM波通道之间相互影响问题

    2020 8 12更新 这次用Cube直接生成PWM控制代码 xff0c 然后再RT Thread Studio上编写程序 xff0c 发现可实现TIM1和TIM8的8路PWM波调控 xff0c 因此上面论述的问题可能是自己在写底层时有某些
  • Ardusub源码解析学习(一)——Ardusub主程序

    APM Sub源码解析学习 xff08 一 xff09 Ardusub主程序 前言一 准备工作二 Ardusub cpp解析2 1 scheduler table2 2 schedulerget scheduler tasks setup
  • Ardusub源码解析学习(二)——电机库

    Ardusub源码解析学习 xff08 二 xff09 电机库学习 一 RC输入与输出1 1 RC Input1 2 RC Output 二 电机库学习2 1 setup motors 2 2 add motor raw 6dof 2 3
  • Ardusub源码解析学习(三)——车辆类型

    APM Sub源码解析学习 xff08 三 xff09 车辆类型 一 前言二 class AP HAL HAL三 class AP Vehicle3 1 h3 2 cpp 四 class Sub4 1 h4 2 cpp 五 总结 一 前言
  • 年度回忆录(2012.10----2013.01)

    寒假结束了 xff0c 年也过完了 xff0c 提前回来一天就开始着手补上这迟到的年终总结 xff0c 写了一个多星期还觉得有些东西没有写出来 xff0c 无奈 xff0c 点到为止吧 2012 年的后半年经历了很多 xff0c 收获了很多
  • Ardusub学习——飞行模式

    参考资料 xff1a Ardusb官方手册 Sub Rework joystick input and pilot input in general Flight Modes Ardusub支持多种飞行模式 xff0c 但是其中一部分需要有
  • Ardusub源码解析学习(五)——从manual model开始

    Ardusub源码解析学习 xff08 五 xff09 从manual model开始 manual init manual run 从本篇开始 xff0c 将会陆续对Ardusub中各种模式进行介绍 xff0c stabilize mod
  • 重读Ardupilot中stabilize model+MAVLINK解包过程

    APM源码和MAVLINK解析学习 重读stabilize stabilize modelinit run handle attitude MAVLINK消息包姿态信息传输过程 之前写的模式都是基于master版本的 xff0c 这次重读s
  • QGC添加自定义组件和发送自定义MAVLINK消息

    QGC添加自定义组件和发送自定义MAVLINK消息 一 添加自定义组件1 1 在飞行界面添加组件1 2 实现组件事件1 3 在MOCK模拟链接中实现验证1 4 验证 二 自定义MAVLINK消息的一些预备知识三 QGC自定义MAVLINK消
  • MAVLINK消息在Ardupilot中的接收和发送过程

    MAVLINK消息在Ardupilot中的接收和发送过程 SCHED TASKupdate receive update send 由于现在网上很多的都是APM旧版本的解释 xff0c 因此把自己的一些学习所得记录下来 截至写博客日期 xf
  • Ardupilot姿态控制器 PID控制流程

    Ardupilot姿态控制器 PID控制流程 一 PID姿态控制器1 1 Copter姿态控制官方原图1 2 ArduCopter V4 X STABILIZE 二 姿态控制器类实现2 1 类成员解析2 1 1 类成员变量2 1 2 类成员
  • APM姿态旋转理论基础

    APM姿态旋转理论基础 一 坐标系1 1 NED坐标系1 2 机体坐标系 二 欧拉角姿态变化率与机体角速度的关系 三 旋转矩阵3 1 基本公式3 2 矩阵作差3 3 旋转矩阵与变换矩阵的区别 四 DCM五 轴角法5 1 基本概念5 2 与旋
  • 详解APM的开方控制器sqrt_controller

    前言 前面说过 xff0c sqrt controller是对P项进行整定用途的 xff0c 目的就是让P项的控制响应 软 下来 xff0c 实际上就是一个经过改进的P控制器 读懂了sqrt controller xff0c 那么你对APM
  • Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析

    Ardupilot前馈及平滑函数input euler angle roll pitch yaw解析 源码解析这个函数做了什么部分细节euler accel limit input shaping angle 姿态变化率与机体角速度之间的关
  • Ardupilot倾转分离函数thrust_heading_rotation_angles

    Ardupilot倾转分离函数thrust heading rotation angles 什么是轴角分离源码分析一些细节补充效果显示及进一步修改 本文主要写一下自己对于APM倾转分离 xff08 轴角分离 xff09 函数的一些学习笔记及
  • Spring IOC原理解析

    首先恭喜守宏同学找到了自己心仪的工作 xff0c 入职的事情终于尘埃落定 xff0c 也算是一个新的开始吧 和守宏聊天的时候也说了很多有关工作的事情 xff0c 畅想了以后美好的未来 xff0c 也想到了今后的种种困难 不说别的就是单单在北
  • Ardupilot四元数姿态控制函数attitude_controller_run_quat解析

    Ardupilot四元数姿态控制函数attitude controller run quat解析 源码解析细节讲解thrust heading rotation angles update ang vel target from att e