OpticalFlow_Onboard.h 2.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  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 <linux/videodev2.h>
  15. #include <AP_HAL/OpticalFlow.h>
  16. #include <AP_Math/AP_Math.h>
  17. #include "AP_HAL_Linux.h"
  18. #include "CameraSensor.h"
  19. #include "Flow_PX4.h"
  20. #include "PWM_Sysfs.h"
  21. #include "VideoIn.h"
  22. #include "AP_HAL/utility/RingBuffer.h"
  23. namespace Linux {
  24. class GyroSample {
  25. public:
  26. Vector2f gyro;
  27. uint64_t time_us;
  28. };
  29. class OpticalFlow_Onboard : public AP_HAL::OpticalFlow {
  30. public:
  31. void init() override;
  32. bool read(AP_HAL::OpticalFlow::Data_Frame& frame) override;
  33. void push_gyro(float gyro_x, float gyro_y, float dt) override;
  34. void push_gyro_bias(float gyro_bias_x, float gyro_bias_y) override;
  35. private:
  36. void _run_optflow();
  37. static void *_read_thread(void *arg);
  38. void _get_integrated_gyros(uint64_t timestamp, GyroSample &gyro);
  39. VideoIn* _videoin;
  40. VideoIn::Frame _last_video_frame;
  41. PWM_Sysfs_Base* _pwm;
  42. CameraSensor* _camerasensor;
  43. Flow_PX4* _flow;
  44. pthread_t _thread;
  45. pthread_mutex_t _mutex;
  46. bool _initialized;
  47. bool _data_available;
  48. bool _crop_by_software;
  49. bool _shrink_by_software;
  50. uint32_t _camera_output_width;
  51. uint32_t _camera_output_height;
  52. uint32_t _width;
  53. uint32_t _height;
  54. uint32_t _format;
  55. uint32_t _bytesperline;
  56. uint32_t _sizeimage;
  57. float _pixel_flow_x_integral;
  58. float _pixel_flow_y_integral;
  59. float _gyro_x_integral;
  60. float _gyro_y_integral;
  61. uint64_t _integration_timespan;
  62. uint8_t _surface_quality;
  63. Vector2f _last_gyro_rate;
  64. Vector2f _gyro_bias;
  65. Vector2f _integrated_gyro;
  66. uint64_t _last_integration_time;
  67. ObjectBuffer<GyroSample> *_gyro_ring_buffer;
  68. };
  69. }