APM:Libraries
AP_InertialSensor_SITL.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 #include <SITL/SITL.h>
4 #include <stdio.h>
5 
6 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
7 
8 const extern AP_HAL::HAL& hal;
9 
12 {
13 }
14 
15 /*
16  detect the sensor
17  */
19 {
21  if (sensor == nullptr) {
22  return nullptr;
23  }
24  if (!sensor->init_sensor()) {
25  delete sensor;
26  return nullptr;
27  }
28  return sensor;
29 }
30 
32 {
34  if (sitl == nullptr) {
35  return false;
36  }
37 
38  // grab the used instances
39  for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
42  }
43 
45 
46  return true;
47 }
48 
49 /*
50  generate an accelerometer sample
51  */
53 {
54  // minimum noise levels are 2 bits, but averaged over many
55  // samples, giving around 0.01 m/s/s
56  float accel_noise = 0.01f;
57 
58  if (sitl->motors_on) {
59  // add extra noise when the motors are on
60  accel_noise += instance==0?sitl->accel_noise:sitl->accel2_noise;
61  }
62 
63  // add accel bias and noise
64  Vector3f accel_bias = instance==0?sitl->accel_bias.get():sitl->accel2_bias.get();
65  float xAccel = sitl->state.xAccel + accel_noise * rand_float() + accel_bias.x;
66  float yAccel = sitl->state.yAccel + accel_noise * rand_float() + accel_bias.y;
67  float zAccel = sitl->state.zAccel + accel_noise * rand_float() + accel_bias.z;
68 
69  // correct for the acceleration due to the IMU position offset and angular acceleration
70  // correct for the centripetal acceleration
71  // only apply corrections to first accelerometer
72  Vector3f pos_offset = sitl->imu_pos_offset;
73  if (!pos_offset.is_zero()) {
74  // calculate sensed acceleration due to lever arm effect
75  // Note: the % operator has been overloaded to provide a cross product
77  Vector3f lever_arm_accel = angular_accel % pos_offset;
78 
79  // calculate sensed acceleration due to centripetal acceleration
81  Vector3f centripetal_accel = angular_rate % (angular_rate % pos_offset);
82 
83  // apply corrections
84  xAccel += lever_arm_accel.x + centripetal_accel.x;
85  yAccel += lever_arm_accel.y + centripetal_accel.y;
86  zAccel += lever_arm_accel.z + centripetal_accel.z;
87  }
88 
89  if (fabsf(sitl->accel_fail) > 1.0e-6f) {
90  xAccel = sitl->accel_fail;
91  yAccel = sitl->accel_fail;
92  zAccel = sitl->accel_fail;
93  }
94 
95  Vector3f accel = Vector3f(xAccel, yAccel, zAccel);
96 
97  _rotate_and_correct_accel(accel_instance[instance], accel);
98 
100 }
101 
102 /*
103  generate a gyro sample
104  */
106 {
107  // minimum gyro noise is less than 1 bit
108  float gyro_noise = ToRad(0.04f);
109 
110  if (sitl->motors_on) {
111  // add extra noise when the motors are on
112  gyro_noise += ToRad(sitl->gyro_noise);
113  }
114 
115  float p = radians(sitl->state.rollRate) + gyro_drift();
116  float q = radians(sitl->state.pitchRate) + gyro_drift();
117  float r = radians(sitl->state.yawRate) + gyro_drift();
118 
119  p += gyro_noise * rand_float();
120  q += gyro_noise * rand_float();
121  r += gyro_noise * rand_float();
122 
123  Vector3f gyro = Vector3f(p, q, r);
124 
125  // add in gyro scaling
126  Vector3f scale = sitl->gyro_scale;
127  gyro.x *= (1 + scale.x*0.01);
128  gyro.y *= (1 + scale.y*0.01);
129  gyro.z *= (1 + scale.z*0.01);
130 
131  _rotate_and_correct_gyro(gyro_instance[instance], gyro);
132 
134 }
135 
137 {
138  uint64_t now = AP_HAL::micros64();
139 #if 0
140  // insert a 1s pause in IMU data. This triggers a pause in EK2
141  // processing that leads to some interesting issues
142  if (now > 5e6 && now < 6e6) {
143  return;
144  }
145 #endif
146  for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
147  if (now >= next_accel_sample[i]) {
148  generate_accel(i);
149  while (now >= next_accel_sample[i]) {
150  next_accel_sample[i] += 1000000UL / accel_sample_hz[i];
151  }
152  }
153  if (now >= next_gyro_sample[i]) {
154  generate_gyro(i);
155  while (now >= next_gyro_sample[i]) {
156  next_gyro_sample[i] += 1000000UL / gyro_sample_hz[i];
157  }
158  }
159  }
160 }
161 
163 {
164  if (sitl->drift_speed == 0.0f ||
165  sitl->drift_time == 0.0f) {
166  return 0;
167  }
168  double period = sitl->drift_time * 2;
169  double minutes = fmod(AP_HAL::micros64() / 60.0e6, period);
170  if (minutes < period/2) {
171  return minutes * ToRad(sitl->drift_speed);
172  }
173  return (period - minutes) * ToRad(sitl->drift_speed);
174 
175 }
176 
177 
179 {
180  for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
183  }
184  return true;
185 }
186 
187 #endif // HAL_BOARD_SITL
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
Vector3< float > Vector3f
Definition: vector3.h:246
double xAccel
Definition: SITL.h:18
#define ToRad(x)
Definition: AP_Common.h:53
Vector3f angAccel
Definition: SITL.h:31
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
AP_Vector3f imu_pos_offset
Definition: SITL.h:178
AP_Vector3f accel2_bias
Definition: SITL.h:94
bool motors_on
Definition: SITL.h:77
double rollRate
Definition: SITL.h:19
void generate_accel(uint8_t instance)
#define INS_SITL_INSTANCES
double yawRate
Definition: SITL.h:19
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
AP_Vector3f gyro_scale
Definition: SITL.h:90
#define f(i)
T y
Definition: vector3.h:67
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
AP_Float gyro_noise
Definition: SITL.h:89
double yAccel
Definition: SITL.h:18
T z
Definition: vector3.h:67
AP_Float drift_speed
Definition: SITL.h:117
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0)
uint64_t micros64()
Definition: system.cpp:162
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro)
double zAccel
Definition: SITL.h:18
AP_Float accel_noise
Definition: SITL.h:91
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false)
uint8_t accel_instance[INS_SITL_INSTANCES]
AP_Vector3f accel_bias
Definition: SITL.h:93
AP_InertialSensor_SITL(AP_InertialSensor &imu)
virtual void register_timer_process(AP_HAL::MemberProc)=0
double pitchRate
Definition: SITL.h:19
const uint16_t accel_sample_hz[INS_SITL_INSTANCES]
static constexpr float radians(float deg)
Definition: AP_Math.h:158
AP_Float accel2_noise
Definition: SITL.h:92
uint64_t next_accel_sample[INS_SITL_INSTANCES]
float rand_float(void)
Definition: AP_Math.cpp:224
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool is_zero(void) const
Definition: vector3.h:159
uint64_t next_gyro_sample[INS_SITL_INSTANCES]
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
AP_Float drift_time
Definition: SITL.h:118
const uint16_t gyro_sample_hz[INS_SITL_INSTANCES]
AP_Float accel_fail
Definition: SITL.h:132
void generate_gyro(uint8_t instance)
uint8_t gyro_instance[INS_SITL_INSTANCES]
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel)
struct sitl_fdm state
Definition: SITL.h:71
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67