OpticalFlow.h 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132
  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. /*
  15. * OpticalFlow.h - OpticalFlow Base Class for Ardupilot
  16. * Code by Randy Mackay. DIYDrones.com
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include <GCS_MAVLink/GCS_MAVLink.h>
  21. class OpticalFlow_backend;
  22. class AP_AHRS_NavEKF;
  23. class OpticalFlow
  24. {
  25. friend class OpticalFlow_backend;
  26. public:
  27. OpticalFlow();
  28. /* Do not allow copies */
  29. OpticalFlow(const OpticalFlow &other) = delete;
  30. OpticalFlow &operator=(const OpticalFlow&) = delete;
  31. // get singleton instance
  32. static OpticalFlow *get_singleton() {
  33. return _singleton;
  34. }
  35. enum class OpticalFlowType {
  36. NONE = 0,
  37. PX4FLOW = 1,
  38. PIXART = 2,
  39. BEBOP = 3,
  40. CXOF = 4,
  41. MAVLINK = 5,
  42. UAVCAN = 6,
  43. SITL = 10
  44. };
  45. // init - initialise sensor
  46. void init(uint32_t log_bit);
  47. // enabled - returns true if optical flow is enabled
  48. bool enabled() const { return _type != (int8_t)OpticalFlowType::NONE; }
  49. // healthy - return true if the sensor is healthy
  50. bool healthy() const { return backend != nullptr && _flags.healthy; }
  51. // read latest values from sensor and fill in x,y and totals.
  52. void update(void);
  53. // handle optical flow mavlink messages
  54. void handle_msg(const mavlink_message_t &msg);
  55. // quality - returns the surface quality as a measure from 0 ~ 255
  56. uint8_t quality() const { return _state.surface_quality; }
  57. // raw - returns the raw movement from the sensor
  58. const Vector2f& flowRate() const { return _state.flowRate; }
  59. // velocity - returns the velocity in m/s
  60. const Vector2f& bodyRate() const { return _state.bodyRate; }
  61. // last_update() - returns system time of last sensor update
  62. uint32_t last_update() const { return _last_update_ms; }
  63. struct OpticalFlow_state {
  64. uint8_t surface_quality; // image quality (below TBD you can't trust the dx,dy values returned)
  65. Vector2f flowRate; // optical flow angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
  66. Vector2f bodyRate; // body inertial angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
  67. };
  68. // return a 3D vector defining the position offset of the sensors focal point in metres relative to the body frame origin
  69. const Vector3f &get_pos_offset(void) const {
  70. return _pos_offset;
  71. }
  72. // parameter var info table
  73. static const struct AP_Param::GroupInfo var_info[];
  74. private:
  75. static OpticalFlow *_singleton;
  76. OpticalFlow_backend *backend;
  77. struct AP_OpticalFlow_Flags {
  78. uint8_t healthy : 1; // true if sensor is healthy
  79. } _flags;
  80. // parameters
  81. AP_Int8 _type; // user configurable sensor type
  82. AP_Int16 _flowScalerX; // X axis flow scale factor correction - parts per thousand
  83. AP_Int16 _flowScalerY; // Y axis flow scale factor correction - parts per thousand
  84. AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees
  85. AP_Vector3f _pos_offset; // position offset of the flow sensor in the body frame
  86. AP_Int8 _address; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow)
  87. // method called by backend to update frontend state:
  88. void update_state(const OpticalFlow_state &state);
  89. // state filled in by backend
  90. struct OpticalFlow_state _state;
  91. uint32_t _last_update_ms; // millis() time of last update
  92. void Log_Write_Optflow();
  93. uint32_t _log_bit = -1; // bitmask bit which indicates if we should log. -1 means we always log
  94. };
  95. namespace AP {
  96. OpticalFlow *opticalflow();
  97. }
  98. #include "OpticalFlow_backend.h"