mirror of
https://github.com/okalachev/flix.git
synced 2025-07-29 20:38:59 +00:00
Rename flu to frd function to match the code style
This commit is contained in:
parent
d4d1797ffc
commit
0a7ed1039f
@ -40,7 +40,7 @@ void sendMavlink() {
|
|||||||
lastFast = t;
|
lastFast = t;
|
||||||
|
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
const float zeroQuat[] = {0, 0, 0, 0};
|
||||||
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
|
Quaternion attitudeFRD = 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, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.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);
|
sendMessage(&msg);
|
||||||
@ -103,7 +103,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
||||||
inline Quaternion FLU2FRD(const Quaternion &q) {
|
inline Quaternion fluToFrd(const Quaternion &q) {
|
||||||
return Quaternion(q.w, q.x, -q.y, -q.z);
|
return Quaternion(q.w, q.x, -q.y, -q.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -44,7 +44,7 @@ void receiveMavlink();
|
|||||||
void handleMavlink(const void *_msg);
|
void handleMavlink(const void *_msg);
|
||||||
void failsafe();
|
void failsafe();
|
||||||
void descend();
|
void descend();
|
||||||
inline Quaternion FLU2FRD(const Quaternion &q);
|
inline Quaternion fluToFrd(const Quaternion &q);
|
||||||
|
|
||||||
// mocks
|
// mocks
|
||||||
void setLED(bool on) {};
|
void setLED(bool on) {};
|
||||||
|
Loading…
x
Reference in New Issue
Block a user