diff --git a/docs/firmware.md b/docs/firmware.md
index d9d33d5..4ad0523 100644
--- a/docs/firmware.md
+++ b/docs/firmware.md
@@ -8,7 +8,7 @@ The firmware is a regular Arduino sketch, and it follows the classic Arduino one
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
-* `t` *(double)* — current step time, *s*.
+* `t` *(float)* — current step time, *s*.
* `dt` *(float)* — time delta between the current and previous steps, *s*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s2*.
diff --git a/flix/cli.ino b/flix/cli.ino
index dc2e22f..eb8d6a5 100644
--- a/flix/cli.ino
+++ b/flix/cli.ino
@@ -9,8 +9,7 @@
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern const int ACRO, STAB, AUTO;
-extern float loopRate, dt;
-extern double t;
+extern float t, dt, loopRate;
extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern int mode;
@@ -60,7 +59,7 @@ void print(const char* format, ...) {
}
void pause(float duration) {
- double start = t;
+ float start = t;
while (t - start < duration) {
step();
handleInput();
diff --git a/flix/flix.ino b/flix/flix.ino
index b63582c..0062f6d 100644
--- a/flix/flix.ino
+++ b/flix/flix.ino
@@ -10,7 +10,7 @@
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1
-double t = NAN; // current step time, s
+float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN;
diff --git a/flix/log.ino b/flix/log.ino
index 1a942ef..396bbed 100644
--- a/flix/log.ino
+++ b/flix/log.ino
@@ -10,7 +10,6 @@
#define LOG_PERIOD 1.0 / LOG_RATE
#define LOG_SIZE LOG_DURATION * LOG_RATE
-float tFloat;
Vector attitudeEuler;
Vector attitudeTargetEuler;
@@ -20,7 +19,7 @@ struct LogEntry {
};
LogEntry logEntries[] = {
- {"t", &tFloat},
+ {"t", &t},
{"rates.x", &rates.x},
{"rates.y", &rates.y},
{"rates.z", &rates.z},
@@ -40,7 +39,6 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
float logBuffer[LOG_SIZE][logColumns];
void prepareLogData() {
- tFloat = t;
attitudeEuler = attitude.toEuler();
attitudeTargetEuler = attitudeTarget.toEuler();
}
@@ -48,7 +46,7 @@ void prepareLogData() {
void logData() {
if (!armed) return;
static int logPointer = 0;
- static double logTime = 0;
+ static float logTime = 0;
if (t - logTime < LOG_PERIOD) return;
logTime = t;
diff --git a/flix/mavlink.ino b/flix/mavlink.ino
index 52a4911..8b30e6a 100644
--- a/flix/mavlink.ino
+++ b/flix/mavlink.ino
@@ -15,7 +15,7 @@
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
-extern double controlTime;
+extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() {
@@ -26,8 +26,8 @@ void processMavlink() {
void sendMavlink() {
sendMavlinkPrint();
- static double lastSlow = 0;
- static double lastFast = 0;
+ static float lastSlow = 0;
+ static float lastFast = 0;
mavlink_message_t msg;
uint32_t time = t * 1000;
diff --git a/flix/parameters.ino b/flix/parameters.ino
index 1f26f6b..494c571 100644
--- a/flix/parameters.ino
+++ b/flix/parameters.ino
@@ -119,7 +119,7 @@ bool setParameter(const char *name, const float value) {
}
void syncParameters() {
- static double lastSync = 0;
+ static float lastSync = 0;
if (t - lastSync < 1) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastSync = t;
diff --git a/flix/rc.ino b/flix/rc.ino
index e9c39b5..21c03ae 100644
--- a/flix/rc.ino
+++ b/flix/rc.ino
@@ -9,7 +9,7 @@
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
uint16_t channels[16]; // raw rc channels
-double controlTime; // time of the last controls update
+float controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
diff --git a/flix/safety.ino b/flix/safety.ino
index 77ddd2a..35ece02 100644
--- a/flix/safety.ino
+++ b/flix/safety.ino
@@ -6,7 +6,7 @@
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10
-extern double controlTime;
+extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() {
diff --git a/flix/time.ino b/flix/time.ino
index 3c6cb0f..b57b5bc 100644
--- a/flix/time.ino
+++ b/flix/time.ino
@@ -6,7 +6,7 @@
float loopRate; // Hz
void step() {
- double now = micros() / 1000000.0;
+ float now = micros() / 1000000.0;
dt = now - t;
t = now;
@@ -18,7 +18,7 @@ void step() {
}
void computeLoopRate() {
- static double windowStart = 0;
+ static float windowStart = 0;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window
diff --git a/flix/util.h b/flix/util.h
index 3946d77..d6ac26d 100644
--- a/flix/util.h
+++ b/flix/util.h
@@ -10,7 +10,7 @@
#include
const float ONE_G = 9.80665;
-extern double t;
+extern float t;
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
diff --git a/gazebo/flix.h b/gazebo/flix.h
index ccc17cc..cc0af04 100644
--- a/gazebo/flix.h
+++ b/gazebo/flix.h
@@ -12,7 +12,7 @@
#define WIFI_ENABLED 1
-double t = NAN;
+float t = NAN;
float dt;
float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;