1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162 |
- #pragma once
- #include "OpticalFlow.h"
- class OpticalFlow_backend
- {
- friend class OpticalFlow;
- public:
-
- OpticalFlow_backend(OpticalFlow &_frontend);
- virtual ~OpticalFlow_backend(void);
-
-
- virtual void init() = 0;
-
- virtual void update() = 0;
-
- virtual void handle_msg(const mavlink_message_t &msg) {}
- protected:
-
- OpticalFlow &frontend;
-
- void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state);
-
- Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); }
-
- float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
-
- void _applyYaw(Vector2f &v);
-
- uint8_t get_address(void) const { return frontend._address; }
-
-
- HAL_Semaphore _sem;
- };
|