SITL: param SITL_ARSP_FAIL should be a float instead of byte

this param was meant to represent an airspeed which is a float
This commit is contained in:
Tom Pittenger 2015-07-27 11:05:50 -07:00 committed by Andrew Tridgell
parent 31fe799757
commit 0c9cec7958
1 changed files with 1 additions and 1 deletions

View File

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