2015-01-02 04:30:32 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2016-02-17 21:25:42 -04:00
|
|
|
#pragma once
|
2015-01-02 04:30:32 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
OpticalFlow backend class for ArduPilot
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "OpticalFlow.h"
|
|
|
|
|
|
|
|
class OpticalFlow_backend
|
|
|
|
{
|
|
|
|
friend class OpticalFlow;
|
|
|
|
|
|
|
|
public:
|
|
|
|
// constructor
|
2016-11-04 20:00:49 -03:00
|
|
|
OpticalFlow_backend(OpticalFlow &_frontend);
|
2016-11-18 05:56:05 -04:00
|
|
|
virtual ~OpticalFlow_backend(void);
|
|
|
|
|
2015-01-02 04:30:32 -04:00
|
|
|
// init - initialise sensor
|
|
|
|
virtual void init() = 0;
|
|
|
|
|
|
|
|
// read latest values from sensor and fill in x,y and totals.
|
|
|
|
virtual void update() = 0;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
// access to frontend
|
|
|
|
OpticalFlow &frontend;
|
|
|
|
|
|
|
|
// update the frontend
|
|
|
|
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state);
|
|
|
|
|
|
|
|
// get the flow scaling parameters
|
|
|
|
Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); }
|
2015-04-06 05:04:24 -03:00
|
|
|
|
|
|
|
// get the yaw angle in radians
|
|
|
|
float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
|
2016-11-04 01:09:19 -03:00
|
|
|
|
2016-11-19 17:22:02 -04:00
|
|
|
// apply yaw angle to a vector
|
|
|
|
void _applyYaw(Vector2f &v);
|
|
|
|
|
2016-11-19 03:18:50 -04:00
|
|
|
// get access to AHRS object
|
|
|
|
AP_AHRS_NavEKF &get_ahrs(void) { return frontend._ahrs; }
|
2016-11-25 23:21:28 -04:00
|
|
|
|
2017-08-21 23:23:18 -03:00
|
|
|
// get ADDR parameter value
|
|
|
|
uint8_t get_address(void) const { return frontend._address; }
|
2016-11-19 03:18:50 -04:00
|
|
|
|
2016-11-04 01:09:19 -03:00
|
|
|
// semaphore for access to shared frontend data
|
|
|
|
AP_HAL::Semaphore *_sem;
|
2015-01-02 04:30:32 -04:00
|
|
|
};
|