mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
SITL: added SIM_SONAR_SCALE parameter
used for simulating different kinds of rangefinders
This commit is contained in:
parent
5bf69d4ab3
commit
ef98eba722
@ -60,6 +60,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||||||
AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
|
AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
|
||||||
AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
|
AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
|
||||||
AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch, 0),
|
AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch, 0),
|
||||||
|
AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -63,6 +63,7 @@ public:
|
|||||||
|
|
||||||
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
|
AP_Float sonar_glitch;// probablility between 0-1 that any given sonar sample will read as max distance
|
||||||
AP_Float sonar_noise; // in metres
|
AP_Float sonar_noise; // in metres
|
||||||
|
AP_Float sonar_scale; // meters per volt
|
||||||
|
|
||||||
AP_Float drift_speed; // degrees/second/minute
|
AP_Float drift_speed; // degrees/second/minute
|
||||||
AP_Float drift_time; // period in minutes
|
AP_Float drift_time; // period in minutes
|
||||||
|
Loading…
Reference in New Issue
Block a user