BatchSampler.cpp 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288
  1. #include "AP_InertialSensor.h"
  2. #include <GCS_MAVLink/GCS.h>
  3. #include <AP_Logger/AP_Logger.h>
  4. // Class level parameters
  5. const AP_Param::GroupInfo AP_InertialSensor::BatchSampler::var_info[] = {
  6. // @Param: BAT_CNT
  7. // @DisplayName: sample count per batch
  8. // @Description: Number of samples to take when logging streams of IMU sensor readings. Will be rounded down to a multiple of 32. This option takes effect on the next reboot.
  9. // @User: Advanced
  10. // @Increment: 32
  11. // @RebootRequired: True
  12. AP_GROUPINFO("BAT_CNT", 1, AP_InertialSensor::BatchSampler, _required_count, 1024),
  13. // @Param: BAT_MASK
  14. // @DisplayName: Sensor Bitmask
  15. // @Description: Bitmap of which IMUs to log batch data for. This option takes effect on the next reboot.
  16. // @User: Advanced
  17. // @Values: 0:None,1:First IMU,255:All
  18. // @Bitmask: 0:IMU1,1:IMU2,2:IMU3
  19. // @RebootRequired: True
  20. AP_GROUPINFO("BAT_MASK", 2, AP_InertialSensor::BatchSampler, _sensor_mask, DEFAULT_IMU_LOG_BAT_MASK),
  21. // @Param: BAT_OPT
  22. // @DisplayName: Batch Logging Options Mask
  23. // @Description: Options for the BatchSampler
  24. // @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP), 1: Sample post-filtering
  25. // @User: Advanced
  26. AP_GROUPINFO("BAT_OPT", 3, AP_InertialSensor::BatchSampler, _batch_options_mask, 0),
  27. // @Param: BAT_LGIN
  28. // @DisplayName: logging interval
  29. // @Description: Interval between pushing samples to the AP_Logger log
  30. // @Units: ms
  31. // @Increment: 10
  32. AP_GROUPINFO("BAT_LGIN", 4, AP_InertialSensor::BatchSampler, push_interval_ms, 20),
  33. // @Param: BAT_LGCT
  34. // @DisplayName: logging count
  35. // @Description: Number of samples to push to count every @PREFIX@BAT_LGIN
  36. // @Increment: 1
  37. AP_GROUPINFO("BAT_LGCT", 5, AP_InertialSensor::BatchSampler, samples_per_msg, 32),
  38. AP_GROUPEND
  39. };
  40. extern const AP_HAL::HAL& hal;
  41. void AP_InertialSensor::BatchSampler::init()
  42. {
  43. if (_sensor_mask == 0) {
  44. return;
  45. }
  46. if (_required_count <= 0) {
  47. return;
  48. }
  49. _required_count -= _required_count % 32; // round down to nearest multiple of 32
  50. const uint32_t total_allocation = 3*_required_count*sizeof(uint16_t);
  51. gcs().send_text(MAV_SEVERITY_DEBUG, "INS: alloc %u bytes for ISB (free=%u)", (unsigned int)total_allocation, (unsigned int)hal.util->available_memory());
  52. data_x = (int16_t*)calloc(_required_count, sizeof(int16_t));
  53. data_y = (int16_t*)calloc(_required_count, sizeof(int16_t));
  54. data_z = (int16_t*)calloc(_required_count, sizeof(int16_t));
  55. if (data_x == nullptr || data_y == nullptr || data_z == nullptr) {
  56. free(data_x);
  57. free(data_y);
  58. free(data_z);
  59. data_x = nullptr;
  60. data_y = nullptr;
  61. data_z = nullptr;
  62. gcs().send_text(MAV_SEVERITY_WARNING, "Failed to allocate %u bytes for IMU batch sampling", (unsigned int)total_allocation);
  63. return;
  64. }
  65. rotate_to_next_sensor();
  66. initialised = true;
  67. }
  68. void AP_InertialSensor::BatchSampler::periodic()
  69. {
  70. if (_sensor_mask == 0) {
  71. return;
  72. }
  73. push_data_to_log();
  74. }
  75. void AP_InertialSensor::BatchSampler::update_doing_sensor_rate_logging()
  76. {
  77. // We can't do post-filter sensor rate logging
  78. if ((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_POST_FILTER) {
  79. _doing_post_filter_logging = true;
  80. _doing_sensor_rate_logging = false;
  81. return;
  82. }
  83. _doing_post_filter_logging = false;
  84. if (!((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_SENSOR_RATE)) {
  85. _doing_sensor_rate_logging = false;
  86. return;
  87. }
  88. const uint8_t bit = (1<<instance);
  89. switch (type) {
  90. case IMU_SENSOR_TYPE_GYRO:
  91. _doing_sensor_rate_logging = _imu._gyro_sensor_rate_sampling_enabled & bit;
  92. break;
  93. case IMU_SENSOR_TYPE_ACCEL:
  94. _doing_sensor_rate_logging = _imu._accel_sensor_rate_sampling_enabled & bit;
  95. break;
  96. }
  97. }
  98. void AP_InertialSensor::BatchSampler::rotate_to_next_sensor()
  99. {
  100. if (_sensor_mask == 0) {
  101. // should not have been called
  102. return;
  103. }
  104. if ((1U<<instance) > (uint8_t)_sensor_mask) {
  105. // should only ever happen if user resets _sensor_mask
  106. instance = 0;
  107. }
  108. if (type == IMU_SENSOR_TYPE_ACCEL) {
  109. // we have logged accelerometers, now log gyros:
  110. type = IMU_SENSOR_TYPE_GYRO;
  111. multiplier = _imu._gyro_raw_sampling_multiplier[instance];
  112. update_doing_sensor_rate_logging();
  113. return;
  114. }
  115. // log for accel sensor:
  116. type = IMU_SENSOR_TYPE_ACCEL;
  117. // move to next IMU backend:
  118. // we assume the number of gyros and accels is the same, taking
  119. // this minimum stops us doing bad things if that isn't true:
  120. const uint8_t _count = MIN(_imu._accel_count, _imu._gyro_count);
  121. // find next backend instance to log:
  122. bool haveinstance = false;
  123. for (uint8_t i=instance+1; i<_count; i++) {
  124. if (_sensor_mask & (1U<<i)) {
  125. instance = i;
  126. haveinstance = true;
  127. break;
  128. }
  129. }
  130. if (!haveinstance) {
  131. for (uint8_t i=0; i<=instance; i++) {
  132. if (_sensor_mask & (1U<<i)) {
  133. instance = i;
  134. haveinstance = true;
  135. break;
  136. }
  137. }
  138. }
  139. if (!haveinstance) {
  140. // should not happen!
  141. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  142. abort();
  143. #endif
  144. instance = 0;
  145. return;
  146. }
  147. multiplier = _imu._accel_raw_sampling_multiplier[instance];
  148. update_doing_sensor_rate_logging();
  149. }
  150. void AP_InertialSensor::BatchSampler::push_data_to_log()
  151. {
  152. if (!initialised) {
  153. return;
  154. }
  155. if (_sensor_mask == 0) {
  156. return;
  157. }
  158. if (data_write_offset - data_read_offset < samples_per_msg) {
  159. // insuffucient data to pack a packet
  160. return;
  161. }
  162. if (AP_HAL::millis() - last_sent_ms < (uint16_t)push_interval_ms) {
  163. // avoid flooding AP_Logger's buffer
  164. return;
  165. }
  166. AP_Logger *logger = AP_Logger::get_singleton();
  167. if (logger == nullptr) {
  168. // should not have been called
  169. return;
  170. }
  171. // possibly send isb header:
  172. if (!isbh_sent && data_read_offset == 0) {
  173. float sample_rate = 0; // avoid warning about uninitialised values
  174. switch(type) {
  175. case IMU_SENSOR_TYPE_GYRO:
  176. sample_rate = _imu._gyro_raw_sample_rates[instance];
  177. if (_doing_sensor_rate_logging) {
  178. sample_rate *= _imu._gyro_over_sampling[instance];
  179. }
  180. break;
  181. case IMU_SENSOR_TYPE_ACCEL:
  182. sample_rate = _imu._accel_raw_sample_rates[instance];
  183. if (_doing_sensor_rate_logging) {
  184. sample_rate *= _imu._accel_over_sampling[instance];
  185. }
  186. break;
  187. }
  188. if (!logger->Write_ISBH(isb_seqnum,
  189. type,
  190. instance,
  191. multiplier,
  192. _required_count,
  193. measurement_started_us,
  194. sample_rate)) {
  195. // buffer full?
  196. return;
  197. }
  198. isbh_sent = true;
  199. }
  200. // pack and send a data packet:
  201. if (!logger->Write_ISBD(isb_seqnum,
  202. data_read_offset/samples_per_msg,
  203. &data_x[data_read_offset],
  204. &data_y[data_read_offset],
  205. &data_z[data_read_offset])) {
  206. // maybe later?!
  207. return;
  208. }
  209. data_read_offset += samples_per_msg;
  210. last_sent_ms = AP_HAL::millis();
  211. if (data_read_offset >= _required_count) {
  212. // that was the last one. Clean up:
  213. data_read_offset = 0;
  214. isb_seqnum++;
  215. isbh_sent = false;
  216. // rotate to next instance:
  217. rotate_to_next_sensor();
  218. data_write_offset = 0; // unlocks writing process
  219. }
  220. }
  221. bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_TYPE _type)
  222. {
  223. if (_sensor_mask == 0) {
  224. return false;
  225. }
  226. if (!initialised) {
  227. return false;
  228. }
  229. if (_instance != instance) {
  230. return false;
  231. }
  232. if (_type != type) {
  233. return false;
  234. }
  235. if (data_write_offset >= _required_count) {
  236. return false;
  237. }
  238. AP_Logger *logger = AP_Logger::get_singleton();
  239. if (logger == nullptr) {
  240. return false;
  241. }
  242. #define MASK_LOG_ANY 0xFFFF
  243. if (!logger->should_log(MASK_LOG_ANY)) {
  244. return false;
  245. }
  246. return true;
  247. }
  248. void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample)
  249. {
  250. if (!should_log(_instance, _type)) {
  251. return;
  252. }
  253. if (data_write_offset == 0) {
  254. measurement_started_us = sample_us;
  255. }
  256. data_x[data_write_offset] = multiplier*_sample.x;
  257. data_y[data_write_offset] = multiplier*_sample.y;
  258. data_z[data_write_offset] = multiplier*_sample.z;
  259. data_write_offset++; // may unblock the reading process
  260. }