mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Replay: added floating point exception checking
allows NaN errors to be caught in gdb
This commit is contained in:
parent
d382fa51ee
commit
7ca08294e7
@ -47,6 +47,7 @@
|
||||
#include <stdio.h>
|
||||
#include <getopt.h>
|
||||
#include <errno.h>
|
||||
#include <fenv.h>
|
||||
|
||||
#include "LogReader.h"
|
||||
|
||||
@ -84,7 +85,7 @@ static FILE *ekf4f;
|
||||
static bool done_parameters;
|
||||
static bool done_baro_init;
|
||||
static bool done_home_init;
|
||||
static uint16_t update_rate;
|
||||
static uint16_t update_rate = 50;
|
||||
static uint32_t arm_time_ms;
|
||||
|
||||
static uint8_t num_user_parameters;
|
||||
@ -179,6 +180,8 @@ void setup()
|
||||
LogReader.wait_type(LOG_GPS_MSG);
|
||||
LogReader.wait_type(LOG_IMU_MSG);
|
||||
|
||||
feenableexcept(FE_INVALID | FE_OVERFLOW);
|
||||
|
||||
ahrs.set_compass(&compass);
|
||||
ahrs.set_fly_forward(true);
|
||||
ahrs.set_wind_estimation(true);
|
||||
|
Loading…
Reference in New Issue
Block a user