SITL: catch floating point errors

if we get a FPE then log a message and exit
This commit is contained in:
Andrew Tridgell 2012-02-14 21:07:08 +11:00
parent c39914e734
commit 812b7ae5ae
1 changed files with 9 additions and 0 deletions

View File

@ -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':