Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析

2023-05-16

Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析

  • 源码解析
  • 这个函数做了什么
  • 部分细节
    • euler_accel_limit()
    • input_shaping_angle()
    • 姿态变化率与机体角速度之间的关系


本文将以input_euler_angle_roll_pitch_yaw()函数为例,讲解一下APM中的前馈及平滑控制函数,当然其余的类似input_euler_angle_roll_pitch_euler_rate_yaw()等等的函数也是类似的,当学习完这个函数之后,其他的上手应该也会很快的。

源码解析

函数名:input_euler_angle_roll_pitch_yaw()

函数位置:ardupilot/libraries/AC_AttitudeControl/AC_AttitudeControl

官方注释:Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing

注:以下内容会尽可能详细注释,力求让大家都看懂,一些细节部分会着重放在后面讲解。其中以n系简称NED坐标系,b系简称机体坐标系,tb表示期望姿态,cb表示当前姿态。

// 通过角速度前馈和平滑控制欧拉角,俯仰角和偏航角
// 前馈控制器控制量计算在此函数中完成
// 前三个输入参数:本次输入的期望姿态的roll、pitch、yaw角
void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
{
    // 角度制转换为弧度制(乘以0.01是因为在输入这个函数之前乘以了100)
    float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
    float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
    float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f);

    // _attitude_target_quat表示当前(未更新本次输入前)的期望姿态的四元数
	// 可以理解为操作员通过遥控器摇杆输入的期望姿态是在实时变更的
	// 这个总函数(input_euler_xxx)的输入是本次输入的期望,而_attitude_target_quat中保存的是还未收到本次输入进行更新前,当下的期望姿态
	// 此处将其转换为欧拉角形式_attitude_target_euler_angle
    _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);

    // 添加侧倾调整以补偿直升机尾部螺旋桨的推力(在多旋翼飞机上将返回零)
    euler_roll_angle += get_roll_trim_rad();

    if (_rate_bf_ff_enabled) {
    	// 如果开启了机体速率前馈,注意下方将期望角度转换为期望角速率的操作表示的是FF前馈控制器的作用
		// FF前馈控制器根据期望姿态误差计算出期望姿态的期望角速率,其是作为前馈控制量叠加到P控制器输出的当前姿态的期望角速率上的

        // 将侧倾、俯仰和偏航的加速度限制转换到欧拉轴上
		// euler_accel_limit()接收当前期望姿态欧拉角和roll、pitch、yaw上最大加速度
		// 以此计算出最小加速度限制,使增加加速度时不会超过任何一个轴的最大加速度
        Vector3f euler_accel = euler_accel_limit(_attitude_target_euler_angle, Vector3f(get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()));

        // 根据本次输入的期望姿态和未更新输入的当前期望姿态的姿态角度误差计算期望欧拉角速率校正值_attitude_target_euler_rate
		// 以roll角为例
		// wrap_PI(euler_roll_angle - _attitude_target_euler_angle.x):计算本次输入期望roll角和当前期望姿态roll角之间的误差,并将其限制在[-pi pi]之间
		// input_tc:姿态控制输入时间常数,数字越小,响应越尖锐;数字越大,响应越柔和,默认设定为0.15
		// euler_accel.x经限制后的欧拉角加速度
		// _attitude_target_euler_rate.x:当前期望姿态欧拉角速率
		// _dt:采样周期
        _attitude_target_euler_rate.x = input_shaping_angle(wrap_PI(euler_roll_angle - _attitude_target_euler_angle.x), _input_tc, euler_accel.x, _attitude_target_euler_rate.x, _dt);
        _attitude_target_euler_rate.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _attitude_target_euler_angle.y), _input_tc, euler_accel.y, _attitude_target_euler_rate.y, _dt);
        _attitude_target_euler_rate.z = input_shaping_angle(wrap_PI(euler_yaw_angle - _attitude_target_euler_angle.z), _input_tc, euler_accel.z, _attitude_target_euler_rate.z, _dt);
        if (slew_yaw) {		// 如果开启了摆率限制,那么还要对期望欧拉角速率进行限制
            _attitude_target_euler_rate.z = constrain_float(_attitude_target_euler_rate.z, -get_slew_yaw_rads(), get_slew_yaw_rads());
        }

        // 将期望姿态的欧拉角速率_attitude_target_euler_rate转换为前馈的期望机体角速度矢量_attitude_target_ang_vel
		// 姿态变化率(n系)转换为期望机体角速度(cb系)
        euler_rate_to_ang_vel(_attitude_target_euler_angle, _attitude_target_euler_rate, _attitude_target_ang_vel);
        // 角速度_attitude_target_ang_vel限幅
        ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
        // 然后将限幅后的期望机体角速度重新转换为所需姿态的欧拉角速率
        ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
        // 最后得到的期望角速率_attitude_target_ang_vel和期望欧拉角速率_attitude_target_euler_rate是前馈速率,即前馈控制量
        // 注意以上运算过程是在本次输入的期望姿态与当前期望姿态之间实现的,最后得到的期望角速率是针对于期望机体坐标系的
        // 因此该期望角速率在使用前需要先转换到当前姿态下
    } else {
        // 如果未启用前馈功能,则将目标欧拉角输入到目标中并将前馈速率归零
        
        // 将本次输入的期望roll和yaw保存进当下的_attitude_target_euler_angle
        _attitude_target_euler_angle.x = euler_roll_angle;
        _attitude_target_euler_angle.y = euler_pitch_angle;
        if (slew_yaw) {
            // 如果开启了摆率限制
			// 计算出本次输入期望yaw角和当前期望yaw角之间的误差,并限幅
            float angle_error = constrain_float(wrap_PI(euler_yaw_angle - _attitude_target_euler_angle.z), -get_slew_yaw_rads() * _dt, get_slew_yaw_rads() * _dt);
            // 根据误差更新yaw角期望姿态
            _attitude_target_euler_angle.z = wrap_PI(angle_error + _attitude_target_euler_angle.z);
        } else {
        	// 如果没有开启摆率限制
			// 直接将本次输入保存为当前期望姿态yaw角
            _attitude_target_euler_angle.z = euler_yaw_angle;
        }
        // 将期望姿态从欧拉角转换为四元数形式(n系下)
        _attitude_target_quat.from_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);

        // 将速率前馈设置为零,即没有前馈量
        _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
        _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
    }

    // 调用四元数姿态控制器(真正的P控制器在其中运行)
	// 根据姿态角误差计算出期望角速率
    attitude_controller_run_quat();
}

 

这个函数做了什么

关于什么是前馈,怎么叠加的,以及APM中的PID控制流程,详见我之前的博文:Ardupilot姿态控制器 PID控制流程

这里还是先放一张APM官方的老图:

在这里插入图片描述

本函数中主要做了以下几件事:

  • 获取到本次输入的期望姿态euler_roll\pitch\yaw_angle(无论是来自遥控器还是地面站MAVLINK消息),以及未更新前(未处理本次输入前)的当下期望姿态_attitude_target_euler_angle(全局变量);
  • 根据是否开启前馈控制分别进行处理:
    • 如果开启了前馈控制:
      1. 根据本次输入的期望和当前期望计算出欧拉角误差,然后计算得出期望欧拉角速率_attitude_target_euler_rate;
      2. 期望欧拉角速率_attitude_target_euler_rate转换为b系下的期望机体角速度_attitude_target_ang_vel并且进行角速度限幅;
      3. 最后重新获取到前馈速率:_attitude_target_euler_rate和_attitude_target_ang_vel;
      4. _attitude_target_quat的更新将在attitude_controller_run_quat()中进行;
    • 如果没有开启前馈控制:
      1. 直接将本次输入的期望姿态保存到全局变量 _attitude_target_euler_angle,并获取四元数形式的期望姿态 _attitude_target_quat;
      2. 然后将前馈速率 _attitude_target_euler_rate和_attitude_target_ang_vel置零。
  • 最后运行四元数姿态控制器,真正的P控制器将在其内部运行。

总结:input_euler_angle_roll_pitch_yaw()这个函数主要在其内部实现了前馈控制量计算及平滑的操作,最后调用了四元数姿态控制器(废话 =.=)。


注意:如果开启了前馈,计算出来的前馈速率 _attitude_target_ang_vel是基于期望姿态 的,因此在使用前,需要先转换到当前姿态坐标系下。

原因:因为input_euler_xxx()里面期望角速率是根据本次输入期望姿态当下期望姿态计算得到(基于tb系),而attitude_controller_run_quat()中的P控制器则是通过当下期望姿态_attitude_target_quat当前姿态的误差计算得到期望角速率(基于cb系)

 

部分细节

euler_accel_limit()

// translates body frame acceleration limits to the euler axis
Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel)
{
    float sin_phi = constrain_float(fabsf(sinf(euler_rad.x)), 0.1f, 1.0f);
    float cos_phi = constrain_float(fabsf(cosf(euler_rad.x)), 0.1f, 1.0f);
    float sin_theta = constrain_float(fabsf(sinf(euler_rad.y)), 0.1f, 1.0f);

    Vector3f rot_accel;
    if (is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) {
        rot_accel.x = euler_accel.x;
        rot_accel.y = euler_accel.y;
        rot_accel.z = euler_accel.z;
    } else {
        rot_accel.x = euler_accel.x;
        rot_accel.y = MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi);
        rot_accel.z = MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / sin_phi), euler_accel.z / cos_phi);
    }
    return rot_accel;
}

原谅我截止到写博文的时间还没有推出这个原型公式到底是什么(然而我还是厚脸皮地放上来了,有大佬懂麻烦留一下言)。然而我可以说一下这个函数的目的到底是啥。

参考资料:Copter: Is there any problem in function euler_accel_limit()?

So the problem here is we need to calculate the acceleration limits that will not let us increase past any one individual axis acceleration limit. I think you are calculating the maximum acceleration limits possible, not the minimum that we need.
So for example, if we are banked over by 45 degrees in roll. If we ask apply full yaw then the acceleration will be shared by both the body pitch and body yaw. However, if we apply full yaw and push the pitch stick forward then that euler yaw acceleration is applied only to the body frame yaw and is increased in magnitude because the aircraft is banked by 45 degrees. So we need to limit the yaw acceleration based on this limit rather than the vector addition of both body pitch and body yaw.

翻译过来的大致意思就是:

这个函数计算加速度极限,该极限让我们增加加速度时不会超过欧拉角上任何一个轴的加速度极限。因此该函数求的是各轴上的最小加速度限制。

举例来说,当我们沿俯仰角倾斜了45°,也就是说机头向上仰起,如果要求完全偏航,此时加速度将会由俯仰和偏航共同承担,但是如果我们施加了完全偏航并且向前推动俯仰杆,欧拉偏航加速度仅应用于机体框架,使得在当前倾斜情况下欧拉角的旋转幅度大于机体的旋转幅度,因此我们需要这个函数来限制偏航加速度。

input_shaping_angle()

这个函数实际上内部调用了sqrt_controller(一个修改过的P控制器)来计算得到前馈控制量_attitude_target_euler_rate。其他的不再多做解释。

关于sqrt_controller的解释,看这篇:详解APM的开方控制器sqrt_controller

// 根据角度误差计算速度校正。 角速度具有加速和减速限制,包括使用_input_tc进行的基本加速度限制
float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float dt)
{
// sqrt_controller作为调整后的P控制器,根据接收到的角度误差计算出期望角速率
// Kp = 1/max(input_tc,0.01)
    float desired_ang_vel = sqrt_controller(error_angle, 1.0f / MAX(input_tc, 0.01f), accel_max, dt);

    // 直接限制加速度以平滑曲线的起点。
    return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt);
}
...
// 限制请求速度的加减速
float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
{
    // 直接限制加速度以平滑曲线的起点。
    if (is_positive(accel_max)) {
        float delta_ang_vel = accel_max * dt;
        return constrain_float(desired_ang_vel, target_ang_vel - delta_ang_vel, target_ang_vel + delta_ang_vel);
    } else {
        return desired_ang_vel;
    }
}

姿态变化率与机体角速度之间的关系

主要是下面两个函数:

// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads)
{
    float sin_theta = sinf(euler_rad.y);
    float cos_theta = cosf(euler_rad.y);
    float sin_phi = sinf(euler_rad.x);
    float cos_phi = cosf(euler_rad.x);

    ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z;
    ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z;
    ang_vel_rads.z = -sin_phi * euler_rate_rads.y + cos_theta * cos_phi * euler_rate_rads.z;
}
// Convert an angular velocity vector to a 321-intrinsic euler angle derivative
// Returns false if the vehicle is pitched 90 degrees up or down
bool AC_AttitudeControl::ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads)
{
    float sin_theta = sinf(euler_rad.y);
    float cos_theta = cosf(euler_rad.y);
    float sin_phi = sinf(euler_rad.x);
    float cos_phi = cosf(euler_rad.x);

    // When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false.
    if (is_zero(cos_theta)) {
        return false;
    }

    euler_rate_rads.x = ang_vel_rads.x + sin_phi * (sin_theta / cos_theta) * ang_vel_rads.y + cos_phi * (sin_theta / cos_theta) * ang_vel_rads.z;
    euler_rate_rads.y = cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z;
    euler_rate_rads.z = (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z;
    return true;
}

实际上一些基础理论我都汇总在了这篇博文里面:APM姿态旋转理论基础

这边还是放一下数学原型,摘自全权老师的《多旋翼飞行器设计与控制》:

在这里插入图片描述
 

如有错误请及时告知

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

Ardupilot前馈及平滑函数input_euler_angle_roll_pitch_yaw解析 的相关文章

  • 导致索引失效的可能情况

    如下是可能导致索引失效的情况 xff1a 1 xff0e 隐式转换导致索引失效 这一点应当引起重视 也是开发中经常会犯的错误 由于表的字段tu mdn定义为varchar2 20 但在查询时把该字段作为number类型以where条件传给O
  • 二叉搜索树的增删查

    今天把搜索二叉树的思路又理了一遍 xff0c 把代码又从头到尾敲了一遍 xff0c 各位看客就不要在意代码粗糙和内存溢出了 xff0c 主要把插入和删除的过程理了一遍 xff0c 其中比较复杂的地方就是搜索二叉树的删除 xff0c 涉及了很
  • 中缀表达式转前缀和后缀表达式

    之前笔试中国电信IT研发中心的时候 xff0c 遇到了几个前 中 后缀表达式的相互转换 xff0c 当时忘得差不多了 xff0c 今天好好把该方面的知识好好复习 xff0c 并把相关代码和思路自己缕了一遍 xff1a 将中缀表达式转换为前缀
  • 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 姿态变化率与机体角速度之间的关