VideoIn.h 2.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586
  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. #pragma once
  14. #include "AP_HAL_Linux.h"
  15. #include <linux/videodev2.h>
  16. #include <vector>
  17. namespace Linux {
  18. struct buffer {
  19. unsigned int size;
  20. void *mem;
  21. };
  22. class VideoIn {
  23. public:
  24. /* This structure implements the fields of the v4l2_pix_format struct
  25. * that are considered useful for an optical flow application along
  26. * with the v4l2_buffer fields timestamp and sequence*/
  27. class Frame {
  28. friend class VideoIn;
  29. public:
  30. uint32_t timestamp;
  31. uint32_t sequence;
  32. void *data;
  33. private:
  34. uint32_t buf_index;
  35. };
  36. bool get_frame(Frame &frame);
  37. void put_frame(Frame &frame);
  38. void set_device_path(const char* path);
  39. void init();
  40. bool open_device(const char *device_path, uint32_t memtype);
  41. bool allocate_buffers(uint32_t nbufs);
  42. void get_pixel_formats(std::vector<uint32_t> *formats);
  43. bool set_format(uint32_t *width, uint32_t *height, uint32_t *format,
  44. uint32_t *bytesperline, uint32_t *sizeimage);
  45. bool set_crop(uint32_t left, uint32_t top,
  46. uint32_t width, uint32_t height);
  47. void prepare_capture();
  48. static void shrink_8bpp(uint8_t *buffer, uint8_t *new_buffer,
  49. uint32_t width, uint32_t height, uint32_t left,
  50. uint32_t selection_width, uint32_t top,
  51. uint32_t selection_height, uint32_t fx, uint32_t fy);
  52. static void crop_8bpp(uint8_t *buffer, uint8_t *new_buffer,
  53. uint32_t width, uint32_t left,
  54. uint32_t crop_width, uint32_t top,
  55. uint32_t crop_height);
  56. static void yuyv_to_grey(uint8_t *buffer, uint32_t buffer_size,
  57. uint8_t *new_buffer);
  58. private:
  59. void _queue_buffer(int index);
  60. bool _set_streaming(bool enable);
  61. bool _dequeue_frame(Frame &frame);
  62. uint32_t _timeval_to_us(struct timeval& tv);
  63. int _fd = -1;
  64. struct buffer *_buffers;
  65. unsigned int _nbufs;
  66. bool _streaming;
  67. uint32_t _width;
  68. uint32_t _height;
  69. uint32_t _format;
  70. uint32_t _bytesperline;
  71. uint32_t _sizeimage;
  72. uint32_t _memtype = V4L2_MEMORY_MMAP;
  73. };
  74. }