123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Math/AP_Math.h>
- #include <GCS_MAVLink/GCS_MAVLink.h>
- class OpticalFlow_backend;
- class AP_AHRS_NavEKF;
- class OpticalFlow
- {
- friend class OpticalFlow_backend;
- public:
- OpticalFlow();
-
- OpticalFlow(const OpticalFlow &other) = delete;
- OpticalFlow &operator=(const OpticalFlow&) = delete;
-
- static OpticalFlow *get_singleton() {
- return _singleton;
- }
- enum class OpticalFlowType {
- NONE = 0,
- PX4FLOW = 1,
- PIXART = 2,
- BEBOP = 3,
- CXOF = 4,
- MAVLINK = 5,
- UAVCAN = 6,
- SITL = 10
- };
-
- void init(uint32_t log_bit);
-
- bool enabled() const { return _type != (int8_t)OpticalFlowType::NONE; }
-
- bool healthy() const { return backend != nullptr && _flags.healthy; }
-
- void update(void);
-
- void handle_msg(const mavlink_message_t &msg);
-
- uint8_t quality() const { return _state.surface_quality; }
-
- const Vector2f& flowRate() const { return _state.flowRate; }
-
- const Vector2f& bodyRate() const { return _state.bodyRate; }
-
- uint32_t last_update() const { return _last_update_ms; }
- struct OpticalFlow_state {
- uint8_t surface_quality;
- Vector2f flowRate;
- Vector2f bodyRate;
- };
-
- const Vector3f &get_pos_offset(void) const {
- return _pos_offset;
- }
-
- static const struct AP_Param::GroupInfo var_info[];
- private:
- static OpticalFlow *_singleton;
- OpticalFlow_backend *backend;
- struct AP_OpticalFlow_Flags {
- uint8_t healthy : 1;
- } _flags;
-
- AP_Int8 _type;
- AP_Int16 _flowScalerX;
- AP_Int16 _flowScalerY;
- AP_Int16 _yawAngle_cd;
- AP_Vector3f _pos_offset;
- AP_Int8 _address;
-
- void update_state(const OpticalFlow_state &state);
-
- struct OpticalFlow_state _state;
- uint32_t _last_update_ms;
- void Log_Write_Optflow();
- uint32_t _log_bit = -1;
- };
- namespace AP {
- OpticalFlow *opticalflow();
- }
- #include "OpticalFlow_backend.h"
|