APM:Libraries
OpticalFlow_backend.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  OpticalFlow backend class for ArduPilot
19  */
20 
21 #include "OpticalFlow.h"
22 
24 {
25  friend class OpticalFlow;
26 
27 public:
28  // constructor
29  OpticalFlow_backend(OpticalFlow &_frontend);
30  virtual ~OpticalFlow_backend(void);
31 
32  // init - initialise sensor
33  virtual void init() = 0;
34 
35  // read latest values from sensor and fill in x,y and totals.
36  virtual void update() = 0;
37 
38 protected:
39  // access to frontend
41 
42  // update the frontend
44 
45  // get the flow scaling parameters
46  Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); }
47 
48  // get the yaw angle in radians
49  float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
50 
51  // apply yaw angle to a vector
52  void _applyYaw(Vector2f &v);
53 
54  // get access to AHRS object
55  AP_AHRS_NavEKF &get_ahrs(void) { return frontend._ahrs; }
56 
57  // get ADDR parameter value
58  uint8_t get_address(void) const { return frontend._address; }
59 
60  // semaphore for access to shared frontend data
62 };
Vector2< float > Vector2f
Definition: vector2.h:239
AP_Int16 _flowScalerY
Definition: OpticalFlow.h:92
void _applyYaw(Vector2f &v)
uint8_t get_address(void) const
AP_AHRS_NavEKF & get_ahrs(void)
Vector2f _flowScaler(void) const
AP_AHRS_NavEKF & _ahrs
Definition: OpticalFlow.h:82
AP_Int16 _flowScalerX
Definition: OpticalFlow.h:91
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
virtual ~OpticalFlow_backend(void)
OpticalFlow_backend(OpticalFlow &_frontend)
static int state
Definition: Util.cpp:20
AP_Int8 _address
Definition: OpticalFlow.h:95
float v
Definition: Printf.cpp:15
float _yawAngleRad(void) const
virtual void init()=0
static constexpr float radians(float deg)
Definition: AP_Math.h:158
AP_Int16 _yawAngle_cd
Definition: OpticalFlow.h:93
AP_HAL::Semaphore * _sem
virtual void update()=0