APM:Libraries
benchmark_videoin.cpp
Go to the documentation of this file.
1 #include <AP_gbenchmark.h>
2 #include <AP_HAL/AP_HAL.h>
3 
4 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\
5  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
6 
7 #include <AP_HAL_Linux/VideoIn.h>
8 
9 static void BM_Crop8bpp(benchmark::State& state)
10 {
11  uint8_t *buffer, *new_buffer;
12  uint32_t width = 640;
13  uint32_t height = 480;
14  uint32_t left = width / 2 - state.range_x() / 2;
15  uint32_t top = height / 2 - state.range_y() / 2;
16 
17  buffer = (uint8_t *)malloc(width * height);
18  if (!buffer) {
19  fprintf(stderr, "error: couldn't malloc buffer\n");
20  return;
21  }
22 
23  new_buffer = (uint8_t *)malloc(state.range_x() * state.range_y());
24  if (!new_buffer) {
25  fprintf(stderr, "error: couldn't malloc new_buffer\n");
26  return;
27  }
28 
29  while (state.KeepRunning()) {
30  Linux::VideoIn::crop_8bpp(buffer, new_buffer, width,
31  left, state.range_x(), top, state.range_y());
32  }
33 
34  free(buffer);
35  free(new_buffer);
36 }
37 
38 BENCHMARK(BM_Crop8bpp)->ArgPair(64, 64)->ArgPair(240, 240)->ArgPair(640, 480);
39 
40 static void BM_YuyvToGrey(benchmark::State& state)
41 {
42  uint8_t *buffer, *new_buffer;
43 
44  buffer = (uint8_t *)malloc(state.range_x());
45  if (!buffer) {
46  fprintf(stderr, "error: couldn't malloc buffer\n");
47  return;
48  }
49 
50  new_buffer = (uint8_t *)malloc(state.range_x() / 2);
51  if (!new_buffer) {
52  fprintf(stderr, "error: couldn't malloc new_buffer\n");
53  return;
54  }
55 
56  while (state.KeepRunning()) {
57  Linux::VideoIn::yuyv_to_grey(buffer, state.range_x(), new_buffer);
58  }
59 
60  free(buffer);
61  free(new_buffer);
62 }
63 
64 BENCHMARK(BM_YuyvToGrey)->Arg(64 * 64)->Arg(320 * 240)->Arg(640 * 480);
65 #endif
66 
67 BENCHMARK_MAIN()
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
BENCHMARK(BM_Crop8bpp) -> ArgPair(64, 64) ->ArgPair(240, 240) ->ArgPair(640, 480)
static void yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size, uint8_t *new_buffer)
Definition: VideoIn.cpp:310
static void BM_Crop8bpp(benchmark::State &state)
static int state
Definition: Util.cpp:20
void * malloc(size_t size)
Definition: malloc.c:61
static void BM_YuyvToGrey(benchmark::State &state)
void free(void *ptr)
Definition: malloc.c:81
static void crop_8bpp(uint8_t *buffer, uint8_t *new_buffer, uint32_t width, uint32_t left, uint32_t crop_width, uint32_t top, uint32_t crop_height)
Definition: VideoIn.cpp:292
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539