APM:Libraries
libraries
AP_HAL
OpticalFlow.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
class
AP_HAL::OpticalFlow
{
18
public
:
19
class
Data_Frame
{
20
public
:
21
float
pixel_flow_x_integral
;
22
float
pixel_flow_y_integral
;
23
float
gyro_x_integral
;
24
float
gyro_y_integral
;
25
uint32_t
delta_time
;
26
uint8_t
quality
;
27
};
28
29
virtual
void
init
() = 0;
30
virtual
bool
read
(
Data_Frame
& frame) = 0;
31
virtual
void
push_gyro
(
float
gyro_x,
float
gyro_y,
float
dt) = 0;
32
virtual
void
push_gyro_bias
(
float
gyro_bias_x,
float
gyro_bias_y) = 0;
33
};
AP_HAL::OpticalFlow::Data_Frame::quality
uint8_t quality
Definition:
OpticalFlow.h:26
AP_HAL::OpticalFlow::push_gyro
virtual void push_gyro(float gyro_x, float gyro_y, float dt)=0
AP_HAL::OpticalFlow::Data_Frame::pixel_flow_x_integral
float pixel_flow_x_integral
Definition:
OpticalFlow.h:21
AP_HAL::OpticalFlow::Data_Frame::delta_time
uint32_t delta_time
Definition:
OpticalFlow.h:25
AP_HAL::OpticalFlow::Data_Frame::gyro_y_integral
float gyro_y_integral
Definition:
OpticalFlow.h:24
AP_HAL::OpticalFlow::Data_Frame::pixel_flow_y_integral
float pixel_flow_y_integral
Definition:
OpticalFlow.h:22
AP_HAL::OpticalFlow::init
virtual void init()=0
AP_HAL::OpticalFlow::Data_Frame::gyro_x_integral
float gyro_x_integral
Definition:
OpticalFlow.h:23
AP_HAL::OpticalFlow::read
virtual bool read(Data_Frame &frame)=0
AP_HAL::OpticalFlow::push_gyro_bias
virtual void push_gyro_bias(float gyro_bias_x, float gyro_bias_y)=0
AP_HAL::OpticalFlow::Data_Frame
Definition:
OpticalFlow.h:19
AP_HAL::OpticalFlow
Definition:
OpticalFlow.h:17
Generated on Sun Jun 17 2018 14:18:48 for APM:Libraries by
1.8.13