mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: use AP_Math rand_float()
This commit is contained in:
parent
2fcecaa7c5
commit
62b826953d
@ -148,12 +148,6 @@ void AP_InertialSensor_SITL::timer_update(void)
|
||||
}
|
||||
}
|
||||
|
||||
// generate a random float between -1 and 1
|
||||
float AP_InertialSensor_SITL::rand_float(void)
|
||||
{
|
||||
return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6;
|
||||
}
|
||||
|
||||
float AP_InertialSensor_SITL::gyro_drift(void)
|
||||
{
|
||||
if (sitl->drift_speed == 0.0f ||
|
||||
|
@ -21,7 +21,6 @@ public:
|
||||
private:
|
||||
bool init_sensor(void);
|
||||
void timer_update();
|
||||
float rand_float(void);
|
||||
float gyro_drift(void);
|
||||
void generate_accel(uint8_t instance);
|
||||
void generate_gyro(uint8_t instance);
|
||||
|
Loading…
Reference in New Issue
Block a user