AP_InertialSensor_SITL.cpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_InertialSensor_SITL.h"
  3. #include <SITL/SITL.h>
  4. #include <stdio.h>
  5. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  6. const extern AP_HAL::HAL& hal;
  7. AP_InertialSensor_SITL::AP_InertialSensor_SITL(AP_InertialSensor &imu) :
  8. AP_InertialSensor_Backend(imu)
  9. {
  10. }
  11. /*
  12. detect the sensor
  13. */
  14. AP_InertialSensor_Backend *AP_InertialSensor_SITL::detect(AP_InertialSensor &_imu)
  15. {
  16. AP_InertialSensor_SITL *sensor = new AP_InertialSensor_SITL(_imu);
  17. if (sensor == nullptr) {
  18. return nullptr;
  19. }
  20. if (!sensor->init_sensor()) {
  21. delete sensor;
  22. return nullptr;
  23. }
  24. return sensor;
  25. }
  26. bool AP_InertialSensor_SITL::init_sensor(void)
  27. {
  28. sitl = AP::sitl();
  29. if (sitl == nullptr) {
  30. return false;
  31. }
  32. // grab the used instances
  33. for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
  34. gyro_instance[i] = _imu.register_gyro(gyro_sample_hz[i],
  35. AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 1, DEVTYPE_SITL));
  36. accel_instance[i] = _imu.register_accel(accel_sample_hz[i],
  37. AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 2, DEVTYPE_SITL));
  38. if (enable_fast_sampling(accel_instance[i])) {
  39. _set_accel_raw_sample_rate(accel_instance[i], accel_sample_hz[i]*4);
  40. }
  41. if (enable_fast_sampling(gyro_instance[i])) {
  42. _set_gyro_raw_sample_rate(gyro_instance[i], gyro_sample_hz[i]*8);
  43. }
  44. }
  45. hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SITL::timer_update, void));
  46. return true;
  47. }
  48. /*
  49. generate an accelerometer sample
  50. */
  51. void AP_InertialSensor_SITL::generate_accel(uint8_t instance)
  52. {
  53. // minimum noise levels are 2 bits, but averaged over many
  54. // samples, giving around 0.01 m/s/s
  55. float accel_noise = 0.01f;
  56. if (sitl->motors_on) {
  57. // add extra noise when the motors are on
  58. accel_noise += instance==0?sitl->accel_noise:sitl->accel2_noise;
  59. }
  60. // add accel bias and noise
  61. Vector3f accel_bias = instance==0?sitl->accel_bias.get():sitl->accel2_bias.get();
  62. float xAccel = sitl->state.xAccel + accel_bias.x;
  63. float yAccel = sitl->state.yAccel + accel_bias.y;
  64. float zAccel = sitl->state.zAccel + accel_bias.z;
  65. const Vector3f &vibe_freq = sitl->vibe_freq;
  66. if (vibe_freq.is_zero()) {
  67. xAccel += accel_noise * rand_float();
  68. yAccel += accel_noise * rand_float();
  69. zAccel += accel_noise * rand_float();
  70. } else {
  71. float t = AP_HAL::micros() * 1.0e-6f;
  72. xAccel += sinf(t * 2 * M_PI * vibe_freq.x) * accel_noise;
  73. yAccel += sinf(t * 2 * M_PI * vibe_freq.y) * accel_noise;
  74. zAccel += sinf(t * 2 * M_PI * vibe_freq.z) * accel_noise;
  75. }
  76. // correct for the acceleration due to the IMU position offset and angular acceleration
  77. // correct for the centripetal acceleration
  78. // only apply corrections to first accelerometer
  79. Vector3f pos_offset = sitl->imu_pos_offset;
  80. if (!pos_offset.is_zero()) {
  81. // calculate sensed acceleration due to lever arm effect
  82. // Note: the % operator has been overloaded to provide a cross product
  83. Vector3f angular_accel = Vector3f(radians(sitl->state.angAccel.x) , radians(sitl->state.angAccel.y) , radians(sitl->state.angAccel.z));
  84. Vector3f lever_arm_accel = angular_accel % pos_offset;
  85. // calculate sensed acceleration due to centripetal acceleration
  86. Vector3f angular_rate = Vector3f(radians(sitl->state.rollRate), radians(sitl->state.pitchRate), radians(sitl->state.yawRate));
  87. Vector3f centripetal_accel = angular_rate % (angular_rate % pos_offset);
  88. // apply corrections
  89. xAccel += lever_arm_accel.x + centripetal_accel.x;
  90. yAccel += lever_arm_accel.y + centripetal_accel.y;
  91. zAccel += lever_arm_accel.z + centripetal_accel.z;
  92. }
  93. if (fabsf(sitl->accel_fail) > 1.0e-6f) {
  94. xAccel = sitl->accel_fail;
  95. yAccel = sitl->accel_fail;
  96. zAccel = sitl->accel_fail;
  97. }
  98. Vector3f accel = Vector3f(xAccel, yAccel, zAccel);
  99. _rotate_and_correct_accel(accel_instance[instance], accel);
  100. uint8_t nsamples = enable_fast_sampling(accel_instance[instance])?4:1;
  101. for (uint8_t i=0; i<nsamples; i++) {
  102. _notify_new_accel_raw_sample(accel_instance[instance], accel);
  103. }
  104. }
  105. /*
  106. generate a gyro sample
  107. */
  108. void AP_InertialSensor_SITL::generate_gyro(uint8_t instance)
  109. {
  110. // minimum gyro noise is less than 1 bit
  111. float gyro_noise = ToRad(0.04f);
  112. if (sitl->motors_on) {
  113. // add extra noise when the motors are on
  114. gyro_noise += ToRad(sitl->gyro_noise);
  115. }
  116. float p = radians(sitl->state.rollRate) + gyro_drift();
  117. float q = radians(sitl->state.pitchRate) + gyro_drift();
  118. float r = radians(sitl->state.yawRate) + gyro_drift();
  119. const Vector3f &vibe_freq = sitl->vibe_freq;
  120. if (vibe_freq.is_zero()) {
  121. p += gyro_noise * rand_float();
  122. q += gyro_noise * rand_float();
  123. r += gyro_noise * rand_float();
  124. } else {
  125. float t = AP_HAL::micros() * 1.0e-6f;
  126. p += sinf(t * 2 * M_PI * vibe_freq.x) * gyro_noise;
  127. q += sinf(t * 2 * M_PI * vibe_freq.y) * gyro_noise;
  128. r += sinf(t * 2 * M_PI * vibe_freq.z) * gyro_noise;
  129. }
  130. Vector3f gyro = Vector3f(p, q, r);
  131. // add in gyro scaling
  132. Vector3f scale = sitl->gyro_scale;
  133. gyro.x *= (1 + scale.x*0.01f);
  134. gyro.y *= (1 + scale.y*0.01f);
  135. gyro.z *= (1 + scale.z*0.01f);
  136. _rotate_and_correct_gyro(gyro_instance[instance], gyro);
  137. uint8_t nsamples = enable_fast_sampling(gyro_instance[instance])?8:1;
  138. for (uint8_t i=0; i<nsamples; i++) {
  139. _notify_new_gyro_raw_sample(gyro_instance[instance], gyro);
  140. }
  141. }
  142. void AP_InertialSensor_SITL::timer_update(void)
  143. {
  144. uint64_t now = AP_HAL::micros64();
  145. #if 0
  146. // insert a 1s pause in IMU data. This triggers a pause in EK2
  147. // processing that leads to some interesting issues
  148. if (now > 5e6 && now < 6e6) {
  149. return;
  150. }
  151. #endif
  152. for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
  153. if (now >= next_accel_sample[i]) {
  154. if (((1U<<i) & sitl->accel_fail_mask) == 0) {
  155. generate_accel(i);
  156. while (now >= next_accel_sample[i]) {
  157. next_accel_sample[i] += 1000000UL / accel_sample_hz[i];
  158. }
  159. }
  160. }
  161. if (now >= next_gyro_sample[i]) {
  162. if (((1U<<i) & sitl->gyro_fail_mask) == 0) {
  163. generate_gyro(i);
  164. while (now >= next_gyro_sample[i]) {
  165. next_gyro_sample[i] += 1000000UL / gyro_sample_hz[i];
  166. }
  167. }
  168. }
  169. }
  170. }
  171. float AP_InertialSensor_SITL::gyro_drift(void)
  172. {
  173. if (is_zero(sitl->drift_speed) ||
  174. is_zero(sitl->drift_time)) {
  175. return 0;
  176. }
  177. double period = sitl->drift_time * 2;
  178. double minutes = fmod(AP_HAL::micros64() / 60.0e6, period);
  179. if (minutes < period/2) {
  180. return minutes * ToRad(sitl->drift_speed);
  181. }
  182. return (period - minutes) * ToRad(sitl->drift_speed);
  183. }
  184. bool AP_InertialSensor_SITL::update(void)
  185. {
  186. for (uint8_t i=0; i<INS_SITL_INSTANCES; i++) {
  187. update_accel(accel_instance[i]);
  188. update_gyro(gyro_instance[i]);
  189. }
  190. return true;
  191. }
  192. #endif // HAL_BOARD_SITL