mirror of https://github.com/ArduPilot/ardupilot
SITL: catch floating point errors
if we get a FPE then log a message and exit
This commit is contained in:
parent
c39914e734
commit
812b7ae5ae
|
@ -15,6 +15,13 @@ void loop(void);
|
|||
// the state of the desktop simulation
|
||||
struct desktop_info desktop_state;
|
||||
|
||||
// catch floating point exceptions
|
||||
static void sig_fpe(int signum)
|
||||
{
|
||||
printf("ERROR: Floating point exception\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
static void usage(void)
|
||||
{
|
||||
printf("Options:\n");
|
||||
|
@ -31,6 +38,8 @@ int main(int argc, char * const argv[])
|
|||
desktop_state.slider = false;
|
||||
gettimeofday(&desktop_state.sketch_start_time, NULL);
|
||||
|
||||
signal(SIGFPE, sig_fpe);
|
||||
|
||||
while ((opt = getopt(argc, argv, "swhr:H:")) != -1) {
|
||||
switch (opt) {
|
||||
case 's':
|
||||
|
|
Loading…
Reference in New Issue