APM:Libraries
Flow_PX4.cpp
Go to the documentation of this file.
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  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
42 #include "Flow_PX4.h"
43 
44 #include <cmath>
45 #include <stdio.h>
46 #include <stdlib.h>
47 
48 extern const AP_HAL::HAL& hal;
49 
50 using namespace Linux;
51 
52 Flow_PX4::Flow_PX4(uint32_t width, uint32_t bytesperline,
53  uint32_t max_flow_pixel,
54  float bottom_flow_feature_threshold,
55  float bottom_flow_value_threshold) :
56  _width(width),
57  _bytesperline(bytesperline),
58  _search_size(max_flow_pixel),
59  _bottom_flow_feature_threshold(bottom_flow_feature_threshold),
60  _bottom_flow_value_threshold(bottom_flow_value_threshold)
61 {
62  /* _pixlo is _search_size + 1 because if we need to evaluate
63  * the subpixels up/left of the first pixel, the index
64  * will be equal to _pixlo - _search_size -1
65  * idem if we need to evaluate the subpixels down/right
66  * the index will be equal to _pixhi + _search_size + 1
67  * which needs to remain inferior to _width - 1
68  */
69  _pixlo = _search_size + 1;
70  _pixhi = _width - 1 - (_search_size + 1);
71  /* 1 block is of size 2*_search_size + 1 + 1 pixel on each
72  * side for subpixel calculation.
73  * So _num_blocks = _width / (2 * _search_size + 3)
74  */
75  _num_blocks = _width / (2 * _search_size + 3);
76  _pixstep = ceilf(((float)(_pixhi - _pixlo)) / _num_blocks);
77 }
78 
87 static inline uint32_t compute_diff(uint8_t *image, uint16_t offx, uint16_t offy,
88  uint16_t row_size, uint8_t window_size)
89 {
90  /* calculate position in image buffer */
91  /* we calc only the 4x4 pattern */
92  uint16_t off = (offy + 2) * row_size + (offx + 2);
93  uint32_t acc = 0;
94  unsigned int i;
95 
96  for (i = 0; i < window_size; i++) {
97  /* accumulate differences between line1/2, 2/3, 3/4 for 4 pixels
98  * starting at offset off
99  */
100  acc += abs(image[off + i] - image[off + i + row_size]);
101  acc += abs(image[off + i + row_size] - image[off + i + 2 * row_size]);
102  acc += abs(image[off + i + 2 * row_size] -
103  image[off + i + 3 * row_size]);
104 
105  /* accumulate differences between col1/2, 2/3, 3/4 for 4 pixels starting
106  * at off
107  */
108  acc += abs(image[off + row_size * i] - image[off + row_size * i + 1]);
109  acc += abs(image[off + row_size * i + 1] -
110  image[off + row_size * i + 2]);
111  acc += abs(image[off + row_size * i + 2] -
112  image[off + row_size * i + 3]);
113  }
114 
115  return acc;
116 }
117 
128 static inline uint32_t compute_sad(uint8_t *image1, uint8_t *image2,
129  uint16_t off1x, uint16_t off1y,
130  uint16_t off2x, uint16_t off2y,
131  uint16_t row_size, uint16_t window_size)
132 {
133  /* calculate position in image buffer
134  * off1 for image1 and off2 for image2
135  */
136  uint16_t off1 = off1y * row_size + off1x;
137  uint16_t off2 = off2y * row_size + off2x;
138  unsigned int i,j;
139  uint32_t acc = 0;
140 
141  for (i = 0; i < window_size; i++) {
142  for (j = 0; j < window_size; j++) {
143  acc += abs(image1[off1 + i + j*row_size] -
144  image2[off2 + i + j*row_size]);
145  }
146  }
147  return acc;
148 }
149 
161 static inline uint32_t compute_subpixel(uint8_t *image1, uint8_t *image2,
162  uint16_t off1x, uint16_t off1y,
163  uint16_t off2x, uint16_t off2y,
164  uint32_t *acc, uint16_t row_size,
165  uint16_t window_size)
166 {
167  /* calculate position in image buffer */
168  uint16_t off1 = off1y * row_size + off1x; // image1
169  uint16_t off2 = off2y * row_size + off2x; // image2
170  uint8_t sub[8];
171  uint16_t i, j, k;
172 
173  memset(acc, 0, window_size * sizeof(uint32_t));
174 
175  for (i = 0; i < window_size; i++) {
176  for (j = 0; j < window_size; j++) {
177  /* the 8 s values are from following positions for each pixel (X):
178  * + - + - + - +
179  * + 5 7 +
180  * + - + 6 + - +
181  * + 4 X 0 +
182  * + - + 2 + - +
183  * + 3 1 +
184  * + - + - + - +
185  */
186 
187  /* subpixel 0 is the mean value of base pixel and
188  * the pixel on the right, subpixel 1 is the mean
189  * value of base pixel, the pixel on the right,
190  * the pixel down from it, and the pixel down on
191  * the right. etc...
192  */
193  sub[0] = (image2[off2 + i + j*row_size] +
194  image2[off2 + i + 1 + j*row_size])/2;
195 
196  sub[1] = (image2[off2 + i + j*row_size] +
197  image2[off2 + i + 1 + j*row_size] +
198  image2[off2 + i + (j+1)*row_size] +
199  image2[off2 + i + 1 + (j+1)*row_size])/4;
200 
201  sub[2] = (image2[off2 + i + j*row_size] +
202  image2[off2 + i + 1 + (j+1)*row_size])/2;
203 
204  sub[3] = (image2[off2 + i + j*row_size] +
205  image2[off2 + i - 1 + j*row_size] +
206  image2[off2 + i - 1 + (j+1)*row_size] +
207  image2[off2 + i + (j+1)*row_size])/4;
208 
209  sub[4] = (image2[off2 + i + j*row_size] +
210  image2[off2 + i - 1 + (j+1)*row_size])/2;
211 
212  sub[5] = (image2[off2 + i + j*row_size] +
213  image2[off2 + i - 1 + j*row_size] +
214  image2[off2 + i - 1 + (j-1)*row_size] +
215  image2[off2 + i + (j-1)*row_size])/4;
216 
217  sub[6] = (image2[off2 + i + j*row_size] +
218  image2[off2 + i + (j-1)*row_size])/2;
219 
220  sub[7] = (image2[off2 + i + j*row_size] +
221  image2[off2 + i + 1 + j*row_size] +
222  image2[off2 + i + (j-1)*row_size] +
223  image2[off2 + i + 1 + (j-1)*row_size])/4;
224 
225  for (k = 0; k < 8; k++) {
226  acc[k] += abs(image1[off1 + i + j*row_size] - sub[k]);
227  }
228  }
229  }
230 
231  return 0;
232 }
233 
234 uint8_t Flow_PX4::compute_flow(uint8_t *image1, uint8_t *image2,
235  uint32_t delta_time, float *pixel_flow_x,
236  float *pixel_flow_y)
237 {
238  /* constants */
239  const int16_t winmin = -_search_size;
240  const int16_t winmax = _search_size;
241  uint16_t i, j;
242  uint32_t acc[2*_search_size];
243  int8_t dirsx[_num_blocks*_num_blocks];
244  int8_t dirsy[_num_blocks*_num_blocks];
245  uint8_t subdirs[_num_blocks*_num_blocks];
246  float meanflowx = 0.0f;
247  float meanflowy = 0.0f;
248  uint16_t meancount = 0;
249  float histflowx = 0.0f;
250  float histflowy = 0.0f;
251 
252  /* iterate over all patterns
253  */
254  for (j = _pixlo; j < _pixhi; j += _pixstep) {
255  for (i = _pixlo; i < _pixhi; i += _pixstep) {
256  /* test pixel if it is suitable for flow tracking */
257  uint32_t diff = compute_diff(image1, i, j, (uint16_t) _bytesperline,
258  _search_size);
259  if (diff < _bottom_flow_feature_threshold) {
260  continue;
261  }
262 
263  uint32_t dist = 0xFFFFFFFF; // set initial distance to "infinity"
264  int8_t sumx = 0;
265  int8_t sumy = 0;
266  int8_t ii, jj;
267 
268  for (jj = winmin; jj <= winmax; jj++) {
269  for (ii = winmin; ii <= winmax; ii++) {
270  uint32_t temp_dist = compute_sad(image1, image2, i, j,
271  i + ii, j + jj,
272  (uint16_t)_bytesperline,
273  2 * _search_size);
274  if (temp_dist < dist) {
275  sumx = ii;
276  sumy = jj;
277  dist = temp_dist;
278  }
279  }
280  }
281 
282  /* acceptance SAD distance threshold */
283  if (dist < _bottom_flow_value_threshold) {
284  meanflowx += (float)sumx;
285  meanflowy += (float) sumy;
286 
287  compute_subpixel(image1, image2, i, j, i + sumx, j + sumy,
288  acc, (uint16_t) _bytesperline,
289  2 * _search_size);
290  uint32_t mindist = dist; // best SAD until now
291  uint8_t mindir = 8; // direction 8 for no direction
292  for (uint8_t k = 0; k < 2 * _search_size; k++) {
293  if (acc[k] < mindist) {
294  // SAD becomes better in direction k
295  mindist = acc[k];
296  mindir = k;
297  }
298  }
299  dirsx[meancount] = sumx;
300  dirsy[meancount] = sumy;
301  subdirs[meancount] = mindir;
302  meancount++;
303  }
304  }
305  }
306 
307  /* evaluate flow calculation */
308  if (meancount > _num_blocks * _num_blocks / 2) {
309  meanflowx /= meancount;
310  meanflowy /= meancount;
311 
312  /* use average of accepted flow values */
313  uint32_t meancount_x = 0;
314  uint32_t meancount_y = 0;
315 
316  for (uint16_t h = 0; h < meancount; h++) {
317  float subdirx = 0.0f;
318  if (subdirs[h] == 0 || subdirs[h] == 1 || subdirs[h] == 7) {
319  subdirx = 0.5f;
320  }
321  if (subdirs[h] == 3 || subdirs[h] == 4 || subdirs[h] == 5) {
322  subdirx = -0.5f;
323  }
324  histflowx += (float)dirsx[h] + subdirx;
325  meancount_x++;
326 
327  float subdiry = 0.0f;
328  if (subdirs[h] == 5 || subdirs[h] == 6 || subdirs[h] == 7) {
329  subdiry = -0.5f;
330  }
331  if (subdirs[h] == 1 || subdirs[h] == 2 || subdirs[h] == 3) {
332  subdiry = 0.5f;
333  }
334  histflowy += (float)dirsy[h] + subdiry;
335  meancount_y++;
336  }
337 
338  histflowx /= meancount_x;
339  histflowy /= meancount_y;
340 
341  *pixel_flow_x = histflowx;
342  *pixel_flow_y = histflowy;
343  } else {
344  *pixel_flow_x = 0.0f;
345  *pixel_flow_y = 0.0f;
346  return 0;
347  }
348 
349  /* calc quality */
350  uint8_t qual = (uint8_t)(meancount * 255 / (_num_blocks*_num_blocks));
351 
352  return qual;
353 }
354 
355 #endif
uint32_t _bytesperline
Definition: Flow_PX4.h:32
float _bottom_flow_feature_threshold
Definition: Flow_PX4.h:33
Flow_PX4(uint32_t width, uint32_t bytesperline, uint32_t max_flow_pixel, float bottom_flow_feature_threshold, float bottom_flow_value_threshold)
Definition: Flow_PX4.cpp:52
uint32_t _search_size
Definition: Flow_PX4.h:31
static uint32_t compute_diff(uint8_t *image, uint16_t offx, uint16_t offy, uint16_t row_size, uint8_t window_size)
Compute the average pixel gradient of all horizontal and vertical steps.
Definition: Flow_PX4.cpp:87
uint32_t _width
Definition: Flow_PX4.h:30
uint16_t _pixhi
Definition: Flow_PX4.h:36
uint8_t _num_blocks
Definition: Flow_PX4.h:38
static uint32_t compute_subpixel(uint8_t *image1, uint8_t *image2, uint16_t off1x, uint16_t off1y, uint16_t off2x, uint16_t off2y, uint32_t *acc, uint16_t row_size, uint16_t window_size)
Compute SAD distances of subpixel shift of two pixel patterns.
Definition: Flow_PX4.cpp:161
uint16_t _pixstep
Definition: Flow_PX4.h:37
#define off
Definition: Config.h:52
static uint32_t compute_sad(uint8_t *image1, uint8_t *image2, uint16_t off1x, uint16_t off1y, uint16_t off2x, uint16_t off2y, uint16_t row_size, uint16_t window_size)
Compute SAD of two pixel windows.
Definition: Flow_PX4.cpp:128
uint16_t _pixlo
Definition: Flow_PX4.h:35
float _bottom_flow_value_threshold
Definition: Flow_PX4.h:34
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint8_t compute_flow(uint8_t *image1, uint8_t *image2, uint32_t delta_time, float *pixel_flow_x, float *pixel_flow_y)
Definition: Flow_PX4.cpp:234