mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
HAL_SITL: added airspeed noise control
This commit is contained in:
parent
5adf4e1706
commit
ede927f68a
@ -122,7 +122,7 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
||||
_ins->set_gyro(Vector3f(p, q, r) + _ins->get_gyro_offsets());
|
||||
_ins->set_accel(Vector3f(xAccel, yAccel, zAccel) + _ins->get_accel_offsets());
|
||||
|
||||
airspeed_pin_value = _airspeed_sensor(airspeed);
|
||||
airspeed_pin_value = _airspeed_sensor(airspeed + (_sitl->aspd_noise * _rand_float()));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -45,6 +45,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
|
||||
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
|
||||
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
|
||||
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -49,8 +49,8 @@ public:
|
||||
AP_Float baro_noise; // in Pascals
|
||||
AP_Float gyro_noise; // in degrees/second
|
||||
AP_Float accel_noise; // in m/s/s
|
||||
AP_Float mag_noise; // in mag units (earth field is 818)
|
||||
AP_Float aspd_noise; // in m/s
|
||||
AP_Float mag_noise; // in mag units (earth field is 818)
|
||||
AP_Float mag_error; // in degrees
|
||||
AP_Float servo_rate; // servo speed in degrees/second
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user