AP_OpticalFlow_CXOF.cpp 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. driver for Cheerson CX-OF optical flow sensor
  15. CXOF serial packet description
  16. byte0: header (0xFE)
  17. byte1: reserved
  18. byte2: x-motion low byte;
  19. byte3: x-motion high byte;
  20. byte4: y-motion low byte;
  21. byte5: y-motion high byte;
  22. byte6: t-motion
  23. byte7: surface quality
  24. byte8: footer (0xAA)
  25. sensor sends packets at 25hz
  26. */
  27. #include <AP_HAL/AP_HAL.h>
  28. #include "AP_OpticalFlow_CXOF.h"
  29. #include <AP_Math/crc.h>
  30. #include <AP_AHRS/AP_AHRS.h>
  31. #include <AP_SerialManager/AP_SerialManager.h>
  32. #include <utility>
  33. #include "OpticalFlow.h"
  34. #include <stdio.h>
  35. #define CXOF_HEADER (uint8_t)0xFE
  36. #define CXOF_FOOTER (uint8_t)0xAA
  37. #define CXOF_FRAME_LENGTH 9
  38. #define CXOF_PIXEL_SCALING (1.76e-3)
  39. #define CXOF_TIMEOUT_SEC 0.3f
  40. extern const AP_HAL::HAL& hal;
  41. // constructor
  42. AP_OpticalFlow_CXOF::AP_OpticalFlow_CXOF(OpticalFlow &_frontend, AP_HAL::UARTDriver *_uart) :
  43. OpticalFlow_backend(_frontend),
  44. uart(_uart)
  45. {
  46. }
  47. // detect the device
  48. AP_OpticalFlow_CXOF *AP_OpticalFlow_CXOF::detect(OpticalFlow &_frontend)
  49. {
  50. AP_SerialManager *serial_manager = AP::serialmanager().get_singleton();
  51. if (serial_manager == nullptr) {
  52. return nullptr;
  53. }
  54. // look for first serial driver with protocol defined as OpticalFlow
  55. // this is the only optical flow sensor which uses the serial protocol
  56. AP_HAL::UARTDriver *uart = serial_manager->find_serial(AP_SerialManager::SerialProtocol_OpticalFlow, 0);
  57. if (uart == nullptr) {
  58. return nullptr;
  59. }
  60. // we have found a serial port so use it
  61. AP_OpticalFlow_CXOF *sensor = new AP_OpticalFlow_CXOF(_frontend, uart);
  62. return sensor;
  63. }
  64. // initialise the sensor
  65. void AP_OpticalFlow_CXOF::init()
  66. {
  67. // sanity check uart
  68. if (uart == nullptr) {
  69. return;
  70. }
  71. // open serial port with baud rate of 19200
  72. uart->begin(19200);
  73. last_frame_us = AP_HAL::micros();
  74. }
  75. // read latest values from sensor and fill in x,y and totals.
  76. void AP_OpticalFlow_CXOF::update(void)
  77. {
  78. // sanity check uart
  79. if (uart == nullptr) {
  80. return;
  81. }
  82. // record gyro values as long as they are being used
  83. // the sanity check of dt below ensures old gyro values are not used
  84. if (gyro_sum_count < 1000) {
  85. const Vector3f& gyro = AP::ahrs_navekf().get_gyro();
  86. gyro_sum.x += gyro.x;
  87. gyro_sum.y += gyro.y;
  88. gyro_sum_count++;
  89. }
  90. // sensor values
  91. int32_t x_sum = 0;
  92. int32_t y_sum = 0;
  93. uint16_t qual_sum = 0;
  94. uint16_t count = 0;
  95. // read any available characters in the serial buffer
  96. int16_t nbytes = uart->available();
  97. while (nbytes-- > 0) {
  98. int16_t r = uart->read();
  99. if (r < 0) {
  100. continue;
  101. }
  102. uint8_t c = (uint8_t)r;
  103. // if buffer is empty and this byte is header, add to buffer
  104. if (buf_len == 0) {
  105. if (c == CXOF_HEADER) {
  106. buf[buf_len++] = c;
  107. }
  108. } else {
  109. // add character to buffer
  110. buf[buf_len++] = c;
  111. // if buffer has 9 items try to decode it
  112. if (buf_len >= CXOF_FRAME_LENGTH) {
  113. // check last character matches footer
  114. if (buf[buf_len-1] != CXOF_FOOTER) {
  115. buf_len = 0;
  116. continue;
  117. }
  118. // decode package
  119. int16_t x_raw = (int16_t)((uint16_t)buf[3] << 8) | buf[2];
  120. int16_t y_raw = (int16_t)((uint16_t)buf[5] << 8) | buf[4];
  121. // add to sum of all readings from sensor this iteration
  122. count++;
  123. x_sum += x_raw;
  124. y_sum += y_raw;
  125. qual_sum += buf[7];
  126. // clear buffer
  127. buf_len = 0;
  128. }
  129. }
  130. }
  131. // return without updating state if no readings
  132. if (count == 0) {
  133. return;
  134. }
  135. struct OpticalFlow::OpticalFlow_state state {};
  136. // average surface quality scaled to be between 0 and 255
  137. state.surface_quality = (constrain_int16(qual_sum / count, 64, 78) - 64) * 255 / 14;
  138. // calculate dt
  139. uint64_t this_frame_us = uart->receive_time_constraint_us(CXOF_FRAME_LENGTH);
  140. if (this_frame_us == 0) {
  141. // for HAL that cannot estimate arrival time in serial buffer use current time
  142. this_frame_us = AP_HAL::micros();
  143. }
  144. float dt = (this_frame_us - last_frame_us) * 1.0e-6;
  145. last_frame_us = this_frame_us;
  146. // sanity check dt
  147. if (is_positive(dt) && (dt < CXOF_TIMEOUT_SEC)) {
  148. // calculate flow values
  149. const Vector2f flowScaler = _flowScaler();
  150. float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
  151. float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;
  152. // copy flow rates to state structure
  153. state.flowRate = Vector2f(((float)x_sum / count) * flowScaleFactorX,
  154. ((float)y_sum / count) * flowScaleFactorY);
  155. state.flowRate *= CXOF_PIXEL_SCALING / dt;
  156. // copy average body rate to state structure
  157. state.bodyRate = Vector2f(gyro_sum.x / gyro_sum_count, gyro_sum.y / gyro_sum_count);
  158. _applyYaw(state.flowRate);
  159. _applyYaw(state.bodyRate);
  160. } else {
  161. // first frame received in some time so cannot calculate flow values
  162. state.flowRate.zero();
  163. state.bodyRate.zero();
  164. }
  165. _update_frontend(state);
  166. // reset gyro sum
  167. gyro_sum.zero();
  168. gyro_sum_count = 0;
  169. }