Arducopter Yaw角分析

2023-05-16

Arducopter Yaw

现梳理一遍Poshold模式下的yaw的情况:


  • 首先从 Copter::fast_loop() –> update_flight_mode()–> Copter::ModePosHold::run()
// get_pilot_desired_heading - transform pilot's yaw input into a desired yaw rate returns desired yaw rate in centi-degrees per second
// 偏航的控制,之间进行比例控制,然后把输出作为内环的控制量,由于偏航通道可以控制无人机顺时针旋转和逆时针旋转,
// 所以这里怎么区分出来的呢?肯定是摇杆中立点是分界线,处理后,往左打是负值,往右是正,区分两个方向。
// 最后得到偏航角速度目标控制量,偏航打杆控制速率,跟横滚,俯仰有所不同。
float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
{
    float yaw_request;

    // calculate yaw rate request
    // acro_y_expo 这个值为0-0.5 用来设置当打杆向一边时,设置旋转速度的快慢
    // acro_yaw_p 这个值为把遥控yaw输入转化为期望旋转速率,越大意味着旋转速率会更大
    if (g2.acro_y_expo <= 0) {
        yaw_request = stick_angle * g.acro_yaw_p;
    } else {
        // expo variables
        float y_in, y_in3, y_out;

        // range check expo
        if (g2.acro_y_expo > 1.0f || g2.acro_y_expo < 0.5f) {
            g2.acro_y_expo = 1.0f;
        }

        // yaw expo
        y_in = float(stick_angle)/ROLL_PITCH_YAW_INPUT_MAX;
        y_in3 = y_in*y_in*y_in;
        y_out = (g2.acro_y_expo * y_in3) + ((1.0f - g2.acro_y_expo) * y_in);
        yaw_request = ROLL_PITCH_YAW_INPUT_MAX * y_out * g.acro_yaw_p;
    }
    // convert pilot input to the desired yaw rate
    // 转化pilot 的输入为期望的yaw速率
    return yaw_request;
}

  • 当无人机在地面ap.land_complete时attitude_control->set_yaw_target_to_current_heading();
    —>shift_ef_yaw_target(degrees(_ahrs.yaw - _attitude_target_euler_angle.z)100.0f);
//改变地球坐标系下的目标yaw角度 ,最终算入四元数中
//shift_ef_yaw_target(degrees(_ahrs.yaw - _attitude_target_euler_angle.z)*100.0f)
void AC_AttitudeControl::shift_ef_yaw_target(float yaw_shift_cd)
{
    float yaw_shift = radians(yaw_shift_cd*0.01f);
    Quaternion _attitude_target_update_quat;
    _attitude_target_update_quat.from_axis_angle(Vector3f(0.0f, 0.0f, yaw_shift));
    _attitude_target_quat = _attitude_target_update_quat*_attitude_target_quat;
}

  • 接下来就是姿态更新器attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0);

// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
{
    // Convert from centidegrees on public interface to radians
    // 转换为弧度且缩小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_rate = radians(euler_yaw_rate_cds*0.01f);

    // calculate the attitude target euler angles
    // 计算所需要的目标姿态欧拉角度
    _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);

    // Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)
    // 在四轴上 get_roll_trim_rad() 为0
    euler_roll_angle += get_roll_trim_rad();
    // 机体坐标系下的前馈 _rate_bf_ff_enabled 开启或者关闭
    if (_rate_bf_ff_enabled) {
        // translate the roll pitch and yaw acceleration limits to the euler axis
        // 将横滚,俯仰和偏航加速度极限转换为欧拉轴  get_accel_yaw_max_radss()为yaw角的最大加速度设置为 27000 cdeg/s/s
        // 总的来说,就是为了限制角度变化的加速度
        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()));

        // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler
        // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration
        // and an exponential decay specified by smoothing_gain at the end.
        //当启用加速限制和前馈时,使用Sqt控制器计算欧拉。
        //角速度将使欧拉角在有限减速下的输入角平稳停止。
        //最后由平滑增益指定的指数衰减。

        _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);

        // When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing
        // the output rate towards the input rate.
        // 缓慢让输出速率朝输入速率变化
        _attitude_target_euler_rate.z = input_shaping_ang_vel(_attitude_target_euler_rate.z, euler_yaw_rate, euler_accel.z, _dt);

        // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward
        // 将实际的姿态的欧拉角导数,转化到机体坐标系中速度矢量,作为前馈速度矢量
        euler_rate_to_ang_vel(_attitude_target_euler_angle, _attitude_target_euler_rate, _attitude_target_ang_vel);
        // Limit the angular velocity
        ang_vel_limit(_attitude_target_ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));
        // Convert body-frame angular velocity into euler angle derivative of desired attitude
        // 转化机体坐标系角度速度到期望姿态欧垃角倒数
        ang_vel_to_euler_rate(_attitude_target_euler_angle, _attitude_target_ang_vel, _attitude_target_euler_rate);
    } else {
        // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.
        _attitude_target_euler_angle.x = euler_roll_angle;
        _attitude_target_euler_angle.y = euler_pitch_angle;
        _attitude_target_euler_angle.z += euler_yaw_rate*_dt;
        // Compute quaternion target attitude
        _attitude_target_quat.from_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);

        // Set rate feedforward requests to zero
        _attitude_target_euler_rate = Vector3f(0.0f, 0.0f, 0.0f);
        _attitude_target_ang_vel = Vector3f(0.0f, 0.0f, 0.0f);
    }

    // Call quaternion attitude controller
    attitude_controller_run_quat();
}

// limits the acceleration and deceleration of a velocity request
float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt)
{
    // Acceleration is limited directly to smooth the beginning of the curve.
    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;
    }
}

  • 当无人机起飞了,takeoff
// update attitude controller targets
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(poshold.roll, poshold.pitch, target_yaw_rate);
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

Arducopter Yaw角分析 的相关文章

随机推荐

  • 最简洁的麦克纳姆轮原理与控制方法

    最简洁的麦克纳姆轮控制原理与控制方法 0 写在前面 对于第一次接触麦轮的小伙伴们肯定是没办法十分清晰地想象出麦轮底盘的各种运动该如何控制的 而在实际使用中 xff0c 麦轮的运动灵活性与控制难度之比又非常高 xff0c 可以说是在比较平整的
  • Nuttx下移植uorb笔记

    Nuttx下移植uorb笔记 之前接触过ros下的消息机制 xff08 生产者 消费者 xff09 模型 xff0c 第一感觉是灵活好用 xff0c 但是在资源有限的嵌入式环境里面 xff0c 邮箱 消息 显得就有点不那么灵活 xff0c
  • 关于ADRC算法以及参数整定(调参)的一些心得体会

    关于ADRC算法以及参数整定 xff08 调参 xff09 的一些心得体会 ADRC xff0c 全称叫做Active Disturbance Rejection Control xff0c 中文名是自抗扰控制技术 这项控制算法是由中科院的
  • boa-0.94.13:CGI中文问题

    为什么中文乱码 用win7 自带的浏览器ie 打开服务器的cgi form html xff0c 在Name 输入框输入 汉字 两个字 xff0c 提交服务器 如图1 图1 返回的是结果为 xff1a Server Got you para
  • 跑通VINS-Fusion全流程

    跑通VINS Fusion全流程 常规安装步骤详见官方1 ROS安装2 ceres solver安装3 VINS Fusion安装4 KITTI数据集下载5 跑通KITTI数据集 常规安装步骤详见官方 https github com HK
  • 带GPS的SLAM数据集汇总

    1 带GPS的相关SLAM数据集 Kitti 部分带部分不带 xff0c 看网站写的很详细 xff0c 数据集很常用 http www cvlibs net datasets kitti eval odometry php CMU Visu
  • 跑通GVINS——港科大新作

    跑通GVINS 港科大新作 0 简介1 环境2 跑通GVINS3 数据集4 相关资料打包下载 xff08 不包括数据集 xff09 6 泡泡机器人解读 港科大又一力作 xff01 vins mono以及vins fusion升级版GVINS
  • GVINS文章暴力翻译(仅供自学)

    GVINS文章暴力翻译 xff08 仅供自学 xff09 摘要1 介绍2 相关工作3 符号和定义A 框架b 状态 4 GNSS基本介绍A GNSS 概述B 伪距测量C 多普勒测量D SPP算法 5 系统概述6 概率公式A 地图估计B 惯性因
  • Vins-fusion用到的kitti数据集轨迹对不齐,使用evo -a转换

    kitti数据集基准问题 下面两个图一个是转换前 xff0c 一个是evo a 转换后的 问题描述 xff1a 现在遇到的问题是groundtruth和估计的位姿没有在一个坐标系中 xff0c 生成的轨迹对不齐 xff0c 需要首先根据位姿
  • 怎样用美图秀秀制作一寸照片

    有些时候 xff0c 老是会埋怨自己的http jingyan baidu com article 73c3ce28c852b7e50243d945 html证件照很难看 xff0c 自己拍的照片又不合格 xff0c 该怎么办呢 这里和大家
  • Realsense D435i关闭IR结构光

    Realsense D435i 关闭IR光 前言环境一次性关闭IR光从源码修改 前言 由于要做Realsense D435i的双目结构光相机标定 xff0c 其中用到了ROS来录制数据包 xff0c 但是结构光会影响标定 xff0c 所以得
  • vins-mono保存、重载地图、evo工具测试

    vins mono保存 重载地图 evo工具测试 地图保存与加载先跑起来修改地图保存的路径保存地图重载地图 evo测评evo工具修改数据格式使用evo绘制轨迹与双目ORB SLAM2进行对比 下面咱们来对vins mono地图进行简单测试
  • C++11新特性简介

    目录 功能扩展与增强 右值概念 类中右值扩展 标准库中右值扩展 内联命名空间 初始化 initialzier list 原始字符串 自定义字面值 类型自动推导 auto decltype 常量表达式函数constexpr 变长模板 空指针n
  • Realsense D435i单目跑ORB_SLAM2(无ROS版)

    主要参考mono euroc这个文件修改 xff0c 把数据源改成realsense的就可以了 如何获取realsense数据 xff0c 在之前的博客也阐述过 Realsense D435i 43 Opencv 获取彩色 深度 IMU数据
  • QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)

    一 QGC开发 显示双GPS RTK信息 1 在sitl中进行仿真 xff0c 虚拟出第二个GPS mavlink发送到地面站 如下图中 xff0c 在mavlink msg gps2 raw h中找到发送第二组gps rtk数据函数mav
  • 03_FreeRTOS 二进制信号量

    03 FreeRTOS 二进制信号量 本文介绍 xff1a 二进制信号量的使用方法 简介信号量 信号量基本上用于将任务与系统中的其他事件同步 在FreeRTOS中 xff0c 信号量是基于队列机制实现的 FreeRTOS中有4种信号量 xf
  • 【首发】 ubuntu20.04安装matlab2021b/matlab2020b

    文章目录 一 下载地址1 1 2021b下载链接 BT 1 2 2021a下载链接1 3 2020b CSDN下载链接 二 MATLAB2021b安装方法2 1 Mount iso文件2 2 通过 install 启动安装程序2 3 输入正
  • 无人机右手定则以及角度大小方向粗判断

    无人机右手定则 xff1a 左力右场 xff0c 知道z轴方向 xff0c 然后就知道了xy轴方向 xff0c 其中x轴为大拇指指向的方向 四旋翼无人机欧拉角角度大小与其状态的关系 xff1a 设大地坐标系为 xff1a E xff08 O
  • NuttX RTOS

    目录 综述 NuttX是什么 看看这些文件和功能 它怎么会是一个小小的操作系统呢 xff1f NuttX讨论组 你想谈谈NuttX的特性吗 xff1f 你需要帮助吗 xff1f 问题吗 错误吗 下载 我在哪里可以买到NuttX xff1f
  • Arducopter Yaw角分析

    Arducopter Yaw 现梳理一遍Poshold模式下的yaw的情况 xff1a 首先从 Copter fast loop gt update flight mode gt Copter ModePosHold run span cl