mirror of https://github.com/ArduPilot/ardupilot
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:
parent
31fe799757
commit
0c9cec7958
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue