benchmark_videoin.cpp 1.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. #include <AP_gbenchmark.h>
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  4. #include <AP_HAL_Linux/VideoIn.h>
  5. static void BM_Crop8bpp(benchmark::State& state)
  6. {
  7. uint8_t *buffer, *new_buffer;
  8. uint32_t width = 640;
  9. uint32_t height = 480;
  10. uint32_t left = width / 2 - state.range_x() / 2;
  11. uint32_t top = height / 2 - state.range_y() / 2;
  12. buffer = (uint8_t *)malloc(width * height);
  13. if (!buffer) {
  14. fprintf(stderr, "error: couldn't malloc buffer\n");
  15. return;
  16. }
  17. new_buffer = (uint8_t *)malloc(state.range_x() * state.range_y());
  18. if (!new_buffer) {
  19. fprintf(stderr, "error: couldn't malloc new_buffer\n");
  20. free(buffer);
  21. return;
  22. }
  23. while (state.KeepRunning()) {
  24. Linux::VideoIn::crop_8bpp(buffer, new_buffer, width,
  25. left, state.range_x(), top, state.range_y());
  26. }
  27. free(buffer);
  28. free(new_buffer);
  29. }
  30. BENCHMARK(BM_Crop8bpp)->ArgPair(64, 64)->ArgPair(240, 240)->ArgPair(640, 480);
  31. static void BM_YuyvToGrey(benchmark::State& state)
  32. {
  33. uint8_t *buffer, *new_buffer;
  34. buffer = (uint8_t *)malloc(state.range_x());
  35. if (!buffer) {
  36. fprintf(stderr, "error: couldn't malloc buffer\n");
  37. return;
  38. }
  39. new_buffer = (uint8_t *)malloc(state.range_x() / 2);
  40. if (!new_buffer) {
  41. fprintf(stderr, "error: couldn't malloc new_buffer\n");
  42. free(buffer);
  43. return;
  44. }
  45. while (state.KeepRunning()) {
  46. Linux::VideoIn::yuyv_to_grey(buffer, state.range_x(), new_buffer);
  47. }
  48. free(buffer);
  49. free(new_buffer);
  50. }
  51. BENCHMARK(BM_YuyvToGrey)->Arg(64 * 64)->Arg(320 * 240)->Arg(640 * 480);
  52. #endif
  53. BENCHMARK_MAIN()