mirror of
https://github.com/okalachev/flix.git
synced 2025-07-29 12:28:59 +00:00
Use double for storing time instead of float
Float precision may be not enough after some time of operating
This commit is contained in:
parent
d4e04c46cd
commit
70f5186c1b
@ -6,7 +6,7 @@
|
|||||||
|
|
||||||
The main loop is running at 1000 Hz. All the dataflow is happening through global variables (for simplicity):
|
The main loop is running at 1000 Hz. All the dataflow is happening through global variables (for simplicity):
|
||||||
|
|
||||||
* `t` *(float)* — current step time, *s*.
|
* `t` *(double)* — current step time, *s*.
|
||||||
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
||||||
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
|
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
|
||||||
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
||||||
|
@ -8,7 +8,7 @@
|
|||||||
|
|
||||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||||
extern float loopRate, dt;
|
extern float loopRate, dt;
|
||||||
extern float t;
|
extern double t;
|
||||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
|
|
||||||
const char* motd =
|
const char* motd =
|
||||||
|
@ -6,7 +6,7 @@
|
|||||||
#define RC_LOSS_TIMEOUT 0.2
|
#define RC_LOSS_TIMEOUT 0.2
|
||||||
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
||||||
|
|
||||||
extern float controlsTime;
|
extern double controlsTime;
|
||||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel;
|
extern int rollChannel, pitchChannel, throttleChannel, yawChannel;
|
||||||
|
|
||||||
void failsafe() {
|
void failsafe() {
|
||||||
|
@ -10,7 +10,7 @@
|
|||||||
#define SERIAL_BAUDRATE 115200
|
#define SERIAL_BAUDRATE 115200
|
||||||
#define WIFI_ENABLED 1
|
#define WIFI_ENABLED 1
|
||||||
|
|
||||||
float t = NAN; // current step time, s
|
double t = NAN; // current step time, s
|
||||||
float dt; // time delta from previous step, s
|
float dt; // time delta from previous step, s
|
||||||
int16_t channels[16]; // raw rc channels
|
int16_t channels[16]; // raw rc channels
|
||||||
float controls[16]; // normalized controls in range [-1..1] ([0..1] for throttle)
|
float controls[16]; // normalized controls in range [-1..1] ([0..1] for throttle)
|
||||||
|
@ -10,6 +10,7 @@
|
|||||||
#define LOG_PERIOD 1.0 / LOG_RATE
|
#define LOG_PERIOD 1.0 / LOG_RATE
|
||||||
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
||||||
|
|
||||||
|
float tFloat;
|
||||||
Vector attitudeEuler;
|
Vector attitudeEuler;
|
||||||
Vector attitudeTargetEuler;
|
Vector attitudeTargetEuler;
|
||||||
|
|
||||||
@ -19,7 +20,7 @@ struct LogEntry {
|
|||||||
};
|
};
|
||||||
|
|
||||||
LogEntry logEntries[] = {
|
LogEntry logEntries[] = {
|
||||||
{"t", &t},
|
{"t", &tFloat},
|
||||||
{"rates.x", &rates.x},
|
{"rates.x", &rates.x},
|
||||||
{"rates.y", &rates.y},
|
{"rates.y", &rates.y},
|
||||||
{"rates.z", &rates.z},
|
{"rates.z", &rates.z},
|
||||||
@ -39,6 +40,7 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
|
|||||||
float logBuffer[LOG_SIZE][logColumns];
|
float logBuffer[LOG_SIZE][logColumns];
|
||||||
|
|
||||||
void prepareLogData() {
|
void prepareLogData() {
|
||||||
|
tFloat = t;
|
||||||
attitudeEuler = attitude.toEulerZYX();
|
attitudeEuler = attitude.toEulerZYX();
|
||||||
attitudeTargetEuler = attitudeTarget.toEulerZYX();
|
attitudeTargetEuler = attitudeTarget.toEulerZYX();
|
||||||
}
|
}
|
||||||
@ -46,7 +48,7 @@ void prepareLogData() {
|
|||||||
void logData() {
|
void logData() {
|
||||||
if (!armed) return;
|
if (!armed) return;
|
||||||
static int logPointer = 0;
|
static int logPointer = 0;
|
||||||
static float logTime = 0;
|
static double logTime = 0;
|
||||||
if (t - logTime < LOG_PERIOD) return;
|
if (t - logTime < LOG_PERIOD) return;
|
||||||
logTime = t;
|
logTime = t;
|
||||||
|
|
||||||
|
@ -13,7 +13,7 @@
|
|||||||
#define MAVLINK_CONTROL_SCALE 0.7f
|
#define MAVLINK_CONTROL_SCALE 0.7f
|
||||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||||
|
|
||||||
extern float controlsTime;
|
extern double controlsTime;
|
||||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
|
|
||||||
void processMavlink() {
|
void processMavlink() {
|
||||||
@ -22,8 +22,8 @@ void processMavlink() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void sendMavlink() {
|
void sendMavlink() {
|
||||||
static float lastSlow = 0;
|
static double lastSlow = 0;
|
||||||
static float lastFast = 0;
|
static double lastFast = 0;
|
||||||
|
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
uint32_t time = t * 1000;
|
uint32_t time = t * 1000;
|
||||||
|
@ -113,7 +113,7 @@ bool setParameter(const char *name, const float value) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void syncParameters() {
|
void syncParameters() {
|
||||||
static float lastSync = 0;
|
static double lastSync = 0;
|
||||||
if (t - lastSync < 1) return; // sync once per second
|
if (t - lastSync < 1) return; // sync once per second
|
||||||
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
||||||
lastSync = t;
|
lastSync = t;
|
||||||
|
@ -14,7 +14,7 @@ int yawChannel = 3;
|
|||||||
int armedChannel = 4;
|
int armedChannel = 4;
|
||||||
int modeChannel = 5;
|
int modeChannel = 5;
|
||||||
|
|
||||||
float controlsTime; // time of the last controls update
|
double controlsTime; // time of the last controls update
|
||||||
float channelNeutral[16] = {NAN}; // first element NAN means not calibrated
|
float channelNeutral[16] = {NAN}; // first element NAN means not calibrated
|
||||||
float channelMax[16];
|
float channelMax[16];
|
||||||
|
|
||||||
|
@ -6,7 +6,7 @@
|
|||||||
float loopRate; // Hz
|
float loopRate; // Hz
|
||||||
|
|
||||||
void step() {
|
void step() {
|
||||||
float now = micros() / 1000000.0;
|
double now = micros() / 1000000.0;
|
||||||
dt = now - t;
|
dt = now - t;
|
||||||
t = now;
|
t = now;
|
||||||
|
|
||||||
@ -18,7 +18,7 @@ void step() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void computeLoopRate() {
|
void computeLoopRate() {
|
||||||
static float windowStart = 0;
|
static double windowStart = 0;
|
||||||
static uint32_t rate = 0;
|
static uint32_t rate = 0;
|
||||||
rate++;
|
rate++;
|
||||||
if (t - windowStart >= 1) { // 1 second window
|
if (t - windowStart >= 1) { // 1 second window
|
||||||
|
@ -12,7 +12,7 @@
|
|||||||
|
|
||||||
#define WIFI_ENABLED 1
|
#define WIFI_ENABLED 1
|
||||||
|
|
||||||
float t = NAN;
|
double t = NAN;
|
||||||
float dt;
|
float dt;
|
||||||
float motors[4];
|
float motors[4];
|
||||||
int16_t channels[16]; // raw rc channels
|
int16_t channels[16]; // raw rc channels
|
||||||
|
Loading…
x
Reference in New Issue
Block a user