AP_NavEKF3_Buffer.h 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197
  1. // EKF Buffer models
  2. // this buffer model is to be used for observation buffers,
  3. // the data is pushed into buffer like any standard ring buffer
  4. // return is based on the sample time provided
  5. template <typename element_type>
  6. class obs_ring_buffer_t
  7. {
  8. public:
  9. struct element_t{
  10. element_type element;
  11. } *buffer;
  12. // initialise buffer, returns false when allocation has failed
  13. bool init(uint32_t size)
  14. {
  15. buffer = new element_t[size];
  16. if(buffer == nullptr)
  17. {
  18. return false;
  19. }
  20. memset((void *)buffer,0,size*sizeof(element_t));
  21. _size = size;
  22. _head = 0;
  23. _tail = 0;
  24. _new_data = false;
  25. return true;
  26. }
  27. /*
  28. * Searches through a ring buffer and return the newest data that is older than the
  29. * time specified by sample_time_ms
  30. * Zeros old data so it cannot not be used again
  31. * Returns false if no data can be found that is less than 100msec old
  32. */
  33. bool recall(element_type &element,uint32_t sample_time)
  34. {
  35. if(!_new_data) {
  36. return false;
  37. }
  38. bool success = false;
  39. uint8_t tail = _tail, bestIndex;
  40. if(_head == tail) {
  41. if (buffer[tail].element.time_ms != 0 && buffer[tail].element.time_ms <= sample_time) {
  42. // if head is equal to tail just check if the data is unused and within time horizon window
  43. if (((sample_time - buffer[tail].element.time_ms) < 100)) {
  44. bestIndex = tail;
  45. success = true;
  46. _new_data = false;
  47. }
  48. }
  49. } else {
  50. while(_head != tail) {
  51. // find a measurement older than the fusion time horizon that we haven't checked before
  52. if (buffer[tail].element.time_ms != 0 && buffer[tail].element.time_ms <= sample_time) {
  53. // Find the most recent non-stale measurement that meets the time horizon criteria
  54. if (((sample_time - buffer[tail].element.time_ms) < 100)) {
  55. bestIndex = tail;
  56. success = true;
  57. }
  58. } else if(buffer[tail].element.time_ms > sample_time){
  59. break;
  60. }
  61. tail = (tail+1)%_size;
  62. }
  63. }
  64. if (success) {
  65. element = buffer[bestIndex].element;
  66. _tail = (bestIndex+1)%_size;
  67. //make time zero to stop using it again,
  68. //resolves corner case of reusing the element when head == tail
  69. buffer[bestIndex].element.time_ms = 0;
  70. return true;
  71. } else {
  72. return false;
  73. }
  74. }
  75. /*
  76. * Writes data and timestamp to a Ring buffer and advances indices that
  77. * define the location of the newest and oldest data
  78. */
  79. inline void push(element_type element)
  80. {
  81. // Advance head to next available index
  82. _head = (_head+1)%_size;
  83. // New data is written at the head
  84. buffer[_head].element = element;
  85. _new_data = true;
  86. }
  87. // writes the same data to all elements in the ring buffer
  88. inline void reset_history(element_type element, uint32_t sample_time) {
  89. for (uint8_t index=0; index<_size; index++) {
  90. buffer[index].element = element;
  91. }
  92. }
  93. // zeroes all data in the ring buffer
  94. inline void reset() {
  95. _head = 0;
  96. _tail = 0;
  97. _new_data = false;
  98. memset((void *)buffer,0,_size*sizeof(element_t));
  99. }
  100. private:
  101. uint8_t _size,_head,_tail,_new_data;
  102. };
  103. // Following buffer model is for IMU data,
  104. // it achieves a distance of sample size
  105. // between youngest and oldest
  106. template <typename element_type>
  107. class imu_ring_buffer_t
  108. {
  109. public:
  110. struct element_t{
  111. element_type element;
  112. } *buffer;
  113. // initialise buffer, returns false when allocation has failed
  114. bool init(uint32_t size)
  115. {
  116. buffer = new element_t[size];
  117. if(buffer == nullptr)
  118. {
  119. return false;
  120. }
  121. memset((void *)buffer,0,size*sizeof(element_t));
  122. _size = size;
  123. _youngest = 0;
  124. _oldest = 0;
  125. return true;
  126. }
  127. /*
  128. * Writes data to a Ring buffer and advances indices that
  129. * define the location of the newest and oldest data
  130. */
  131. inline void push_youngest_element(element_type element)
  132. {
  133. // push youngest to the buffer
  134. _youngest = (_youngest+1)%_size;
  135. buffer[_youngest].element = element;
  136. // set oldest data index
  137. _oldest = (_youngest+1)%_size;
  138. if (_oldest == 0) {
  139. _filled = true;
  140. }
  141. }
  142. // return true if the buffer has been filled at least once
  143. inline bool is_filled(void) const {
  144. return _filled;
  145. }
  146. // retrieve the oldest data from the ring buffer tail
  147. inline element_type pop_oldest_element() {
  148. element_type ret = buffer[_oldest].element;
  149. return ret;
  150. }
  151. // writes the same data to all elements in the ring buffer
  152. inline void reset_history(element_type element) {
  153. for (uint8_t index=0; index<_size; index++) {
  154. buffer[index].element = element;
  155. }
  156. }
  157. // zeroes all data in the ring buffer
  158. inline void reset() {
  159. _youngest = 0;
  160. _oldest = 0;
  161. memset((void *)buffer,0,_size*sizeof(element_t));
  162. }
  163. // retrieves data from the ring buffer at a specified index
  164. inline element_type& operator[](uint32_t index) {
  165. return buffer[index].element;
  166. }
  167. // returns the index for the ring buffer oldest data
  168. inline uint8_t get_oldest_index(){
  169. return _oldest;
  170. }
  171. // returns the index for the ring buffer youngest data
  172. inline uint8_t get_youngest_index(){
  173. return _youngest;
  174. }
  175. private:
  176. uint8_t _size,_oldest,_youngest;
  177. bool _filled;
  178. };