Skip to content

9改6问题 #92

@Iiguoren

Description

@Iiguoren

作者大大我看代码发现主要变动在imuconvert中对RPY改为单位矩阵,而在后面transformupdate中与磁力计数据按照权重融合时候并没有关掉这个融合,这个RPY的单位阵不会有影响吗
``
if (cloudInfo.imu_available == true)
{
if (std::abs(cloudInfo.imu_pitch_init) < 1.4)
{
double imuWeight = imuRPYWeight;
tf2::Quaternion imuQuaternion;
tf2::Quaternion transformQuaternion;
double rollMid, pitchMid, yawMid;

            // slerp roll
            transformQuaternion.setRPY(transformTobeMapped[0], 0, 0);
            imuQuaternion.setRPY(cloudInfo.imu_roll_init, 0, 0);
            tf2::Matrix3x3(transformQuaternion.slerp(imuQuaternion, imuWeight)).getRPY(rollMid, pitchMid, yawMid);
            transformTobeMapped[0] = rollMid;

            // slerp pitch
            transformQuaternion.setRPY(0, transformTobeMapped[1], 0);
            imuQuaternion.setRPY(0, cloudInfo.imu_pitch_init, 0);
            tf2::Matrix3x3(transformQuaternion.slerp(imuQuaternion, imuWeight)).getRPY(rollMid, pitchMid, yawMid);
            transformTobeMapped[1] = pitchMid;
        }
    }

``

Metadata

Metadata

Assignees

No one assigned

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions