133 if ((message.sysid != vehicle->
id()) || (message.compid != vehicle->
compId())) {
137 if (_receivingAttitudeQuaternion) {
141 mavlink_attitude_t attitude{};
142 mavlink_msg_attitude_decode(&message, &attitude);
144 _handleAttitudeWorker(attitude.roll, attitude.pitch, attitude.yaw);
165 if ((message.sysid != vehicle->
id()) || (message.compid != vehicle->
compId())) {
169 _receivingAttitudeQuaternion =
true;
171 mavlink_attitude_quaternion_t attitudeQuaternion{};
172 mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);
174 QQuaternion quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
175 QVector3D rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
176 QQuaternion repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);
179 if (repr_offset.length() >= 0.5f) {
181 rates = repr_offset * rates;
184 float attRoll, attPitch, attYaw;
185 float q[] = { quat.scalar(), quat.x(), quat.y(), quat.z() };
186 mavlink_quaternion_to_euler(q, &attRoll, &attPitch, &attYaw);
188 _handleAttitudeWorker(attRoll, attPitch, attYaw);