Arducopter Yaw角分析

本文详细介绍了Arducopter飞行控制系统中Poshold模式下的偏航控制逻辑,包括如何通过遥控器输入调整偏航角速度、控制算法的具体实现,以及在不同飞行状态下的偏航目标设定。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

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);
<think>好的,用户想进行与yaw相关的地面平整度实验,可能用于校准传感器或设备。首先需要理解yaw在这里的作用。Yaw通常指的是绕垂直轴的旋转度,也就是偏航。在地面平整度实验中,如果设备(比如自动驾驶车辆或移动机器人)的yaw存在偏差,可能会影响对地面倾斜度的测量,因为方向不正确会导致传感器数据误解。 接下来要考虑的是如何应用yaw来计算平整度。可能需要通过传感器(如IMU或LiDAR)获取地面的三维数据,并结合设备的姿态(包括yaw)进行坐标变换,将原始数据转换到全局坐标系中。这样能消除设备自身方向变化带来的影响,准确分析地面的高低起伏。 然后,计算平整度可能需要使用统计学方法,比如计算高程的标准差,或者利用曲面拟合后的残差。这里的关键步骤是将传感器数据与yaw结合,确保测量基准正确。例如,如果设备在移动过程中yaw发生变化,需要实时调整数据坐标系,避免因方向偏差导致的地面倾斜误判。 另外,用户提到的校准传感器,可能涉及到通过已知平整的地面来验证和调整yaw的测量准确性。比如,在水平地面上移动设备,记录yaw的变化,如果存在偏差,则需要进行补偿或校准算法。 还需要考虑实验的具体设置,比如使用哪些传感器,数据采集的频率,以及如何处理动态环境中的噪声。引用中的LiDAR SLAM问题提到垂直方向位姿变化导致匹配困难,这可能与地面平整度有关,如果地面不平整,车辆的姿态变化会更复杂,影响yaw的计算和传感器的准确性。因此,在实验中可能需要结合前端里程计和后端优化,确保位姿估计的准确性,从而准确计算地面平整度。 最后,生成相关问题时,需要覆盖yaw的测量方法、数据处理、误差来源以及与其他传感器的融合等方面,帮助用户全面理解实验设计和可能遇到的挑战。</think>### Yaw在地面平整度实验中的应用及计算方法 #### 1. **Yaw的核心作用** Yaw(偏航)是描述物体绕垂直轴旋转的度,在地面平整度实验中主要用于: - **坐标系对齐**:消除设备自身方向变化对地面高程测量的干扰[^2] - **运动轨迹修正**:补偿设备行进方向偏差对连续测量结果的影响 - **多传感器融合**:与俯仰(Pitch)、横滚(Roll)共同构成三维姿态基准 #### 2. **实验实施步骤** **步骤1:建立测量基准** $$ R_z(\psi) = \begin{bmatrix} \cos\psi & -\sin\psi & 0 \\ \sin\psi & \cos\psi & 0 \\ 0 & 0 & 1 \end{bmatrix} $$ 使用旋转矩阵将LiDAR/相机数据转换到全局坐标系[^2] **步骤2:数据采集** - 通过IMU获取实时姿态(含yaw) - LiDAR扫描获取点云数据$(x_i,y_i,z_i)$ - 相机获取纹理信息(可选)[^4] **步骤3:平整度计算** 采用高程标准差指标: $$ \sigma = \sqrt{\frac{1}{N}\sum_{i=1}^{N}(z_i - \bar{z})^2} $$ 其中$\bar{z}$为区域平均高程 #### 3. **关键算法实现** ```python import numpy as np def calculate_flatness(point_cloud, yaw): # 坐标系旋转 theta = np.radians(yaw) rot_matrix = np.array([[np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)]]) rotated_xy = np.dot(point_cloud[:,:2], rot_matrix.T) # 高程统计分析 z_values = point_cloud[:,2] std_dev = np.std(z_values) max_diff = np.max(z_values) - np.min(z_values) return std_dev, max_diff ``` #### 4. **误差控制要点** - **动态补偿**:采用卡尔曼滤波处理IMU漂移 - **多帧融合**:通过SLAM后端优化累计误差 - **地面分割**:使用RANSAC算法分离地面与非地面点云
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Gkbytes

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值