Flow_PX4.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354
  1. /****************************************************************************
  2. *
  3. * Copyright (C) 2013 PX4 Development Team. All rights reserved.
  4. * Author: Petri Tanskanen <tpetri@inf.ethz.ch>
  5. * Lorenz Meier <lm@inf.ethz.ch>
  6. * Samuel Zihlmann <samuezih@ee.ethz.ch>
  7. *
  8. * Modified to fit the APM framework by:
  9. * Julien BERAUD <julien.beraud@parrot.com>
  10. *
  11. * Redistribution and use in source and binary forms, with or without
  12. * modification, are permitted provided that the following conditions
  13. * are met:
  14. *
  15. * 1. Redistributions of source code must retain the above copyright
  16. * notice, this list of conditions and the following disclaimer.
  17. * 2. Redistributions in binary form must reproduce the above copyright
  18. * notice, this list of conditions and the following disclaimer in
  19. * the documentation and/or other materials provided with the
  20. * distribution.
  21. * 3. Neither the name PX4 nor the names of its contributors may be
  22. * used to endorse or promote products derived from this software
  23. * without specific prior written permission.
  24. *
  25. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  26. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  27. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  28. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  29. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  30. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  31. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  32. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  33. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  34. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  35. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  36. * POSSIBILITY OF SUCH DAMAGE.
  37. *
  38. ****************************************************************************/
  39. #include <AP_HAL/AP_HAL.h>
  40. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  41. #include "Flow_PX4.h"
  42. #include <cmath>
  43. #include <stdio.h>
  44. #include <stdlib.h>
  45. extern const AP_HAL::HAL& hal;
  46. using namespace Linux;
  47. Flow_PX4::Flow_PX4(uint32_t width, uint32_t bytesperline,
  48. uint32_t max_flow_pixel,
  49. float bottom_flow_feature_threshold,
  50. float bottom_flow_value_threshold) :
  51. _width(width),
  52. _bytesperline(bytesperline),
  53. _search_size(max_flow_pixel),
  54. _bottom_flow_feature_threshold(bottom_flow_feature_threshold),
  55. _bottom_flow_value_threshold(bottom_flow_value_threshold)
  56. {
  57. /* _pixlo is _search_size + 1 because if we need to evaluate
  58. * the subpixels up/left of the first pixel, the index
  59. * will be equal to _pixlo - _search_size -1
  60. * idem if we need to evaluate the subpixels down/right
  61. * the index will be equal to _pixhi + _search_size + 1
  62. * which needs to remain inferior to _width - 1
  63. */
  64. _pixlo = _search_size + 1;
  65. _pixhi = _width - 1 - (_search_size + 1);
  66. /* 1 block is of size 2*_search_size + 1 + 1 pixel on each
  67. * side for subpixel calculation.
  68. * So _num_blocks = _width / (2 * _search_size + 3)
  69. */
  70. _num_blocks = _width / (2 * _search_size + 3);
  71. _pixstep = ceilf(((float)(_pixhi - _pixlo)) / _num_blocks);
  72. }
  73. /**
  74. * @brief Compute the average pixel gradient of all horizontal and vertical
  75. * steps
  76. *
  77. * @param image ...
  78. * @param offX x coordinate of upper left corner of 8x8 pattern in image
  79. * @param offY y coordinate of upper left corner of 8x8 pattern in image
  80. */
  81. static inline uint32_t compute_diff(uint8_t *image, uint16_t offx, uint16_t offy,
  82. uint16_t row_size, uint8_t window_size)
  83. {
  84. /* calculate position in image buffer */
  85. /* we calc only the 4x4 pattern */
  86. uint16_t off = (offy + 2) * row_size + (offx + 2);
  87. uint32_t acc = 0;
  88. unsigned int i;
  89. for (i = 0; i < window_size; i++) {
  90. /* accumulate differences between line1/2, 2/3, 3/4 for 4 pixels
  91. * starting at offset off
  92. */
  93. acc += abs(image[off + i] - image[off + i + row_size]);
  94. acc += abs(image[off + i + row_size] - image[off + i + 2 * row_size]);
  95. acc += abs(image[off + i + 2 * row_size] -
  96. image[off + i + 3 * row_size]);
  97. /* accumulate differences between col1/2, 2/3, 3/4 for 4 pixels starting
  98. * at off
  99. */
  100. acc += abs(image[off + row_size * i] - image[off + row_size * i + 1]);
  101. acc += abs(image[off + row_size * i + 1] -
  102. image[off + row_size * i + 2]);
  103. acc += abs(image[off + row_size * i + 2] -
  104. image[off + row_size * i + 3]);
  105. }
  106. return acc;
  107. }
  108. /**
  109. * @brief Compute SAD of two pixel windows.
  110. *
  111. * @param image1 ...
  112. * @param image2 ...
  113. * @param off1X x coordinate of upper left corner of pattern in image1
  114. * @param off1Y y coordinate of upper left corner of pattern in image1
  115. * @param off2X x coordinate of upper left corner of pattern in image2
  116. * @param off2Y y coordinate of upper left corner of pattern in image2
  117. */
  118. static inline uint32_t compute_sad(uint8_t *image1, uint8_t *image2,
  119. uint16_t off1x, uint16_t off1y,
  120. uint16_t off2x, uint16_t off2y,
  121. uint16_t row_size, uint16_t window_size)
  122. {
  123. /* calculate position in image buffer
  124. * off1 for image1 and off2 for image2
  125. */
  126. uint16_t off1 = off1y * row_size + off1x;
  127. uint16_t off2 = off2y * row_size + off2x;
  128. unsigned int i,j;
  129. uint32_t acc = 0;
  130. for (i = 0; i < window_size; i++) {
  131. for (j = 0; j < window_size; j++) {
  132. acc += abs(image1[off1 + i + j*row_size] -
  133. image2[off2 + i + j*row_size]);
  134. }
  135. }
  136. return acc;
  137. }
  138. /**
  139. * @brief Compute SAD distances of subpixel shift of two pixel patterns.
  140. *
  141. * @param image1 ...
  142. * @param image2 ...
  143. * @param off1X x coordinate of upper left corner of pattern in image1
  144. * @param off1Y y coordinate of upper left corner of pattern in image1
  145. * @param off2X x coordinate of upper left corner of pattern in image2
  146. * @param off2Y y coordinate of upper left corner of pattern in image2
  147. * @param acc array to store SAD distances for shift in every direction
  148. */
  149. static inline uint32_t compute_subpixel(uint8_t *image1, uint8_t *image2,
  150. uint16_t off1x, uint16_t off1y,
  151. uint16_t off2x, uint16_t off2y,
  152. uint32_t *acc, uint16_t row_size,
  153. uint16_t window_size)
  154. {
  155. /* calculate position in image buffer */
  156. uint16_t off1 = off1y * row_size + off1x; // image1
  157. uint16_t off2 = off2y * row_size + off2x; // image2
  158. uint8_t sub[8];
  159. uint16_t i, j, k;
  160. memset(acc, 0, window_size * sizeof(uint32_t));
  161. for (i = 0; i < window_size; i++) {
  162. for (j = 0; j < window_size; j++) {
  163. /* the 8 s values are from following positions for each pixel (X):
  164. * + - + - + - +
  165. * + 5 7 +
  166. * + - + 6 + - +
  167. * + 4 X 0 +
  168. * + - + 2 + - +
  169. * + 3 1 +
  170. * + - + - + - +
  171. */
  172. /* subpixel 0 is the mean value of base pixel and
  173. * the pixel on the right, subpixel 1 is the mean
  174. * value of base pixel, the pixel on the right,
  175. * the pixel down from it, and the pixel down on
  176. * the right. etc...
  177. */
  178. sub[0] = (image2[off2 + i + j*row_size] +
  179. image2[off2 + i + 1 + j*row_size])/2;
  180. sub[1] = (image2[off2 + i + j*row_size] +
  181. image2[off2 + i + 1 + j*row_size] +
  182. image2[off2 + i + (j+1)*row_size] +
  183. image2[off2 + i + 1 + (j+1)*row_size])/4;
  184. sub[2] = (image2[off2 + i + j*row_size] +
  185. image2[off2 + i + 1 + (j+1)*row_size])/2;
  186. sub[3] = (image2[off2 + i + j*row_size] +
  187. image2[off2 + i - 1 + j*row_size] +
  188. image2[off2 + i - 1 + (j+1)*row_size] +
  189. image2[off2 + i + (j+1)*row_size])/4;
  190. sub[4] = (image2[off2 + i + j*row_size] +
  191. image2[off2 + i - 1 + (j+1)*row_size])/2;
  192. sub[5] = (image2[off2 + i + j*row_size] +
  193. image2[off2 + i - 1 + j*row_size] +
  194. image2[off2 + i - 1 + (j-1)*row_size] +
  195. image2[off2 + i + (j-1)*row_size])/4;
  196. sub[6] = (image2[off2 + i + j*row_size] +
  197. image2[off2 + i + (j-1)*row_size])/2;
  198. sub[7] = (image2[off2 + i + j*row_size] +
  199. image2[off2 + i + 1 + j*row_size] +
  200. image2[off2 + i + (j-1)*row_size] +
  201. image2[off2 + i + 1 + (j-1)*row_size])/4;
  202. for (k = 0; k < 8; k++) {
  203. acc[k] += abs(image1[off1 + i + j*row_size] - sub[k]);
  204. }
  205. }
  206. }
  207. return 0;
  208. }
  209. uint8_t Flow_PX4::compute_flow(uint8_t *image1, uint8_t *image2,
  210. uint32_t delta_time, float *pixel_flow_x,
  211. float *pixel_flow_y)
  212. {
  213. /* constants */
  214. const int16_t winmin = -_search_size;
  215. const int16_t winmax = _search_size;
  216. uint16_t i, j;
  217. uint32_t acc[2*_search_size];
  218. int8_t dirsx[_num_blocks*_num_blocks];
  219. int8_t dirsy[_num_blocks*_num_blocks];
  220. uint8_t subdirs[_num_blocks*_num_blocks];
  221. float meanflowx = 0.0f;
  222. float meanflowy = 0.0f;
  223. uint16_t meancount = 0;
  224. float histflowx = 0.0f;
  225. float histflowy = 0.0f;
  226. /* iterate over all patterns
  227. */
  228. for (j = _pixlo; j < _pixhi; j += _pixstep) {
  229. for (i = _pixlo; i < _pixhi; i += _pixstep) {
  230. /* test pixel if it is suitable for flow tracking */
  231. uint32_t diff = compute_diff(image1, i, j, (uint16_t) _bytesperline,
  232. _search_size);
  233. if (diff < _bottom_flow_feature_threshold) {
  234. continue;
  235. }
  236. uint32_t dist = 0xFFFFFFFF; // set initial distance to "infinity"
  237. int8_t sumx = 0;
  238. int8_t sumy = 0;
  239. int8_t ii, jj;
  240. for (jj = winmin; jj <= winmax; jj++) {
  241. for (ii = winmin; ii <= winmax; ii++) {
  242. uint32_t temp_dist = compute_sad(image1, image2, i, j,
  243. i + ii, j + jj,
  244. (uint16_t)_bytesperline,
  245. 2 * _search_size);
  246. if (temp_dist < dist) {
  247. sumx = ii;
  248. sumy = jj;
  249. dist = temp_dist;
  250. }
  251. }
  252. }
  253. /* acceptance SAD distance threshold */
  254. if (dist < _bottom_flow_value_threshold) {
  255. meanflowx += (float)sumx;
  256. meanflowy += (float) sumy;
  257. compute_subpixel(image1, image2, i, j, i + sumx, j + sumy,
  258. acc, (uint16_t) _bytesperline,
  259. 2 * _search_size);
  260. uint32_t mindist = dist; // best SAD until now
  261. uint8_t mindir = 8; // direction 8 for no direction
  262. for (uint8_t k = 0; k < 2 * _search_size; k++) {
  263. if (acc[k] < mindist) {
  264. // SAD becomes better in direction k
  265. mindist = acc[k];
  266. mindir = k;
  267. }
  268. }
  269. dirsx[meancount] = sumx;
  270. dirsy[meancount] = sumy;
  271. subdirs[meancount] = mindir;
  272. meancount++;
  273. }
  274. }
  275. }
  276. /* evaluate flow calculation */
  277. if (meancount > _num_blocks * _num_blocks / 2) {
  278. meanflowx /= meancount;
  279. meanflowy /= meancount;
  280. /* use average of accepted flow values */
  281. uint32_t meancount_x = 0;
  282. uint32_t meancount_y = 0;
  283. for (uint16_t h = 0; h < meancount; h++) {
  284. float subdirx = 0.0f;
  285. if (subdirs[h] == 0 || subdirs[h] == 1 || subdirs[h] == 7) {
  286. subdirx = 0.5f;
  287. }
  288. if (subdirs[h] == 3 || subdirs[h] == 4 || subdirs[h] == 5) {
  289. subdirx = -0.5f;
  290. }
  291. histflowx += (float)dirsx[h] + subdirx;
  292. meancount_x++;
  293. float subdiry = 0.0f;
  294. if (subdirs[h] == 5 || subdirs[h] == 6 || subdirs[h] == 7) {
  295. subdiry = -0.5f;
  296. }
  297. if (subdirs[h] == 1 || subdirs[h] == 2 || subdirs[h] == 3) {
  298. subdiry = 0.5f;
  299. }
  300. histflowy += (float)dirsy[h] + subdiry;
  301. meancount_y++;
  302. }
  303. histflowx /= meancount_x;
  304. histflowy /= meancount_y;
  305. *pixel_flow_x = histflowx;
  306. *pixel_flow_y = histflowy;
  307. } else {
  308. *pixel_flow_x = 0.0f;
  309. *pixel_flow_y = 0.0f;
  310. return 0;
  311. }
  312. /* calc quality */
  313. uint8_t qual = (uint8_t)(meancount * 255 / (_num_blocks*_num_blocks));
  314. return qual;
  315. }
  316. #endif