mirror of https://github.com/ArduPilot/ardupilot
HAL_AVR_SITL: integrate ACC_BIAS and BARO_GLITCH
Adjust simulated accelerometer values and barometer altitude
This commit is contained in:
parent
79291f25a0
commit
5f1f619829
|
@ -53,6 +53,9 @@ void SITL_State::_update_barometer(float altitude)
|
|||
sim_alt += _sitl->baro_drift * now / 1000;
|
||||
sim_alt += _sitl->baro_noise * _rand_float();
|
||||
|
||||
// add baro glitch
|
||||
sim_alt += _sitl->baro_glitch;
|
||||
|
||||
_barometer->setHIL(sim_alt);
|
||||
}
|
||||
|
||||
|
|
|
@ -149,9 +149,11 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
|||
accel_noise += _sitl->accel_noise;
|
||||
gyro_noise += ToRad(_sitl->gyro_noise);
|
||||
}
|
||||
float xAccel1 = xAccel + accel_noise * _rand_float();
|
||||
float yAccel1 = yAccel + accel_noise * _rand_float();
|
||||
float zAccel1 = zAccel + accel_noise * _rand_float();
|
||||
// get accel bias (add only to first accelerometer)
|
||||
Vector3f accel_bias = _sitl->accel_bias.get();
|
||||
float xAccel1 = xAccel + accel_noise * _rand_float() + accel_bias.x;
|
||||
float yAccel1 = yAccel + accel_noise * _rand_float() + accel_bias.y;
|
||||
float zAccel1 = zAccel + accel_noise * _rand_float() + accel_bias.z;
|
||||
|
||||
float xAccel2 = xAccel + accel_noise * _rand_float();
|
||||
float yAccel2 = yAccel + accel_noise * _rand_float();
|
||||
|
|
Loading…
Reference in New Issue