mirror of https://github.com/ArduPilot/ardupilot
SITL: match plane3.9.0
This commit is contained in:
parent
7c0e7e81b5
commit
50b9e19f5a
|
@ -118,6 +118,9 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
|||
AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
|
||||
AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
|
||||
AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
|
||||
AP_GROUPINFO("MAG_DIA", 18, SITL, mag_diag, 0),
|
||||
AP_GROUPINFO("MAG_ODI", 19, SITL, mag_offdiag, 0),
|
||||
AP_GROUPINFO("MAG_ORIENT", 20, SITL, mag_orient, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -108,6 +108,9 @@ public:
|
|||
AP_Float mag_error; // in degrees
|
||||
AP_Vector3f mag_mot; // in mag units per amp
|
||||
AP_Vector3f mag_ofs; // in mag units
|
||||
AP_Vector3f mag_diag; // diagonal corrections
|
||||
AP_Vector3f mag_offdiag; // off-diagonal corrections
|
||||
AP_Int8 mag_orient; // external compass orientation
|
||||
AP_Float servo_speed; // servo speed in seconds
|
||||
|
||||
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
|
||||
|
|
Loading…
Reference in New Issue