From 0c9cec79588afbb9ccb3038e2fff16a9d57d157c Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 27 Jul 2015 11:05:50 -0700 Subject: [PATCH] SITL: param SITL_ARSP_FAIL should be a float instead of byte this param was meant to represent an airspeed which is a float --- libraries/SITL/SITL.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index d54d28e9c3..964d396cea 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -62,7 +62,7 @@ public: AP_Float accel2_noise; // in m/s/s AP_Vector3f accel_bias; // in m/s/s AP_Float aspd_noise; // in m/s - AP_Int8 aspd_fail; // pitot tube failure + AP_Float aspd_fail; // pitot tube failure AP_Float mag_noise; // in mag units (earth field is 818) AP_Float mag_error; // in degrees