You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
68 lines
2.0 KiB
68 lines
2.0 KiB
10 years ago
|
/*
|
||
|
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/>.
|
||
|
*/
|
||
9 years ago
|
#pragma once
|
||
10 years ago
|
|
||
|
/*
|
||
|
OpticalFlow backend class for ArduPilot
|
||
|
*/
|
||
|
|
||
3 years ago
|
#include "AP_OpticalFlow.h"
|
||
10 years ago
|
|
||
|
class OpticalFlow_backend
|
||
|
{
|
||
|
friend class OpticalFlow;
|
||
|
|
||
|
public:
|
||
|
// constructor
|
||
8 years ago
|
OpticalFlow_backend(OpticalFlow &_frontend);
|
||
8 years ago
|
virtual ~OpticalFlow_backend(void);
|
||
|
|
||
10 years ago
|
// init - initialise sensor
|
||
|
virtual void init() = 0;
|
||
|
|
||
|
// read latest values from sensor and fill in x,y and totals.
|
||
|
virtual void update() = 0;
|
||
|
|
||
6 years ago
|
// handle optical flow mavlink messages
|
||
6 years ago
|
virtual void handle_msg(const mavlink_message_t &msg) {}
|
||
6 years ago
|
|
||
5 years ago
|
#if HAL_MSP_OPTICALFLOW_ENABLED
|
||
5 years ago
|
// handle optical flow msp messages
|
||
5 years ago
|
virtual void handle_msp(const MSP::msp_opflow_data_message_t &pkt) {}
|
||
5 years ago
|
#endif
|
||
5 years ago
|
|
||
10 years ago
|
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); }
|
||
10 years ago
|
|
||
|
// get the yaw angle in radians
|
||
|
float _yawAngleRad(void) const { return radians(float(frontend._yawAngle_cd) * 0.01f); }
|
||
8 years ago
|
|
||
8 years ago
|
// apply yaw angle to a vector
|
||
|
void _applyYaw(Vector2f &v);
|
||
8 years ago
|
|
||
8 years ago
|
// get ADDR parameter value
|
||
|
uint8_t get_address(void) const { return frontend._address; }
|
||
8 years ago
|
|
||
8 years ago
|
// semaphore for access to shared frontend data
|
||
6 years ago
|
HAL_Semaphore _sem;
|
||
10 years ago
|
};
|