diff --git a/flix/mavlink.ino b/flix/mavlink.ino index b42052b..088910d 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -47,9 +47,9 @@ void sendMavlink() { lastFast = t; const float zeroQuat[] = {0, 0, 0, 0}; - Quaternion attitudeFRD = fluToFrd(attitude); // MAVLink uses FRD coordinate system + Quaternion att = fluToFrd(attitude); // MAVLink uses FRD coordinate system 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, att.w, att.x, att.y, att.z, rates.x, rates.y, rates.z, zeroQuat); sendMessage(&msg); mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlsTime * 1000, 0, diff --git a/gazebo/models/flix/flix.sdf b/gazebo/models/flix/flix.sdf index 2c0863d..a374f3a 100644 --- a/gazebo/models/flix/flix.sdf +++ b/gazebo/models/flix/flix.sdf @@ -1,6 +1,7 @@ + 0.065 @@ -23,38 +24,14 @@ 1000 - - - 0.00174533 - - - - - 0.00174533 - - - - - 0.00174533 - - + 0.00174533 + 0.00174533 + 0.00174533 - - - 0.0784 - - - - - 0.0784 - - - - - 0.0784 - - + 0.0784 + 0.0784 + 0.0784 @@ -90,6 +67,5 @@ 1 1 1 0.51 1 1 0.5 -