mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 09:39:33 +00:00
Fix rates, acc and gyro coordinate frame in mavlink
All of them should be in frd. Get rid of fluToFrd function - there is no big need for it.
This commit is contained in:
parent
29f1a2b22b
commit
5eccb3f0c4
@ -49,9 +49,8 @@ void sendMavlink() {
|
|||||||
lastFast = t;
|
lastFast = t;
|
||||||
|
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
const float zeroQuat[] = {0, 0, 0, 0};
|
||||||
Quaternion att = fluToFrd(attitude); // MAVLink uses FRD coordinate system
|
|
||||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||||
time, att.w, att.x, att.y, att.z, rates.x, rates.y, rates.z, zeroQuat);
|
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
|
|
||||||
mavlink_msg_rc_channels_raw_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
mavlink_msg_rc_channels_raw_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
||||||
@ -64,8 +63,8 @@ void sendMavlink() {
|
|||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
|
|
||||||
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
|
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
|
||||||
acc.x * 1000, acc.y * 1000, acc.z * 1000,
|
acc.x * 1000, -acc.y * 1000, -acc.z * 1000, // convert to frd
|
||||||
gyro.x * 1000, gyro.y * 1000, gyro.z * 1000,
|
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
||||||
0, 0, 0, 0);
|
0, 0, 0, 0);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
@ -215,9 +214,4 @@ void sendMavlinkPrint() {
|
|||||||
mavlinkPrintBuffer.clear();
|
mavlinkPrintBuffer.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
|
||||||
inline Quaternion fluToFrd(const Quaternion &q) {
|
|
||||||
return Quaternion(q.w, q.x, -q.y, -q.z);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
x
Reference in New Issue
Block a user