mirror of
https://github.com/okalachev/flix.git
synced 2026-01-12 22:17:45 +00:00
Use FLU as the main coordinate system instead of FRD
Corresponding to the IMU orientation in the new version
This commit is contained in:
@@ -38,8 +38,9 @@ void sendMavlink() {
|
||||
lastFast = t;
|
||||
|
||||
const float zeroQuat[] = {0, 0, 0, 0};
|
||||
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
|
||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
time, attitude.w, attitude.x, attitude.y, attitude.z, rates.x, rates.y, rates.z, zeroQuat);
|
||||
time, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.z, rates.x, rates.y, rates.z, zeroQuat);
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0,
|
||||
@@ -97,4 +98,9 @@ void handleMavlink(const void *_msg) {
|
||||
}
|
||||
}
|
||||
|
||||
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
||||
inline Quaternion FLU2FRD(const Quaternion &q) {
|
||||
return Quaternion(q.w, q.x, -q.y, -q.z);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user