APM:Libraries
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 /*
18  * OpticalFlow.h - OpticalFlow Base Class for Ardupilot
19  * Code by Randy Mackay. DIYDrones.com
20  */
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include <AP_Math/AP_Math.h>
24 
26 class AP_AHRS_NavEKF;
27 
29 {
30  friend class OpticalFlow_backend;
31 
32 public:
34 
35  /* Do not allow copies */
36  OpticalFlow(const OpticalFlow &other) = delete;
37  OpticalFlow &operator=(const OpticalFlow&) = delete;
38 
39  // init - initialise sensor
40  void init(void);
41 
42  // enabled - returns true if optical flow is enabled
43  bool enabled() const { return _enabled; }
44 
45  // healthy - return true if the sensor is healthy
46  bool healthy() const { return backend != nullptr && _flags.healthy; }
47 
48  // read latest values from sensor and fill in x,y and totals.
49  void update(void);
50 
51  // quality - returns the surface quality as a measure from 0 ~ 255
52  uint8_t quality() const { return _state.surface_quality; }
53 
54  // raw - returns the raw movement from the sensor
55  const Vector2f& flowRate() const { return _state.flowRate; }
56 
57  // velocity - returns the velocity in m/s
58  const Vector2f& bodyRate() const { return _state.bodyRate; }
59 
60  // device_id - returns device id
61  uint8_t device_id() const { return _state.device_id; }
62 
63  // last_update() - returns system time of last sensor update
64  uint32_t last_update() const { return _last_update_ms; }
65 
67  uint8_t device_id; // device id
68  uint8_t surface_quality; // image quality (below TBD you can't trust the dx,dy values returned)
69  Vector2f flowRate; // optical flow angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
70  Vector2f bodyRate; // body inertial angular rate in rad/sec measured about the X and Y body axis. A RH rotation about a sensor axis produces a positive rate.
71  };
72 
73  // return a 3D vector defining the position offset of the sensors focal point in metres relative to the body frame origin
74  const Vector3f &get_pos_offset(void) const {
75  return _pos_offset;
76  }
77 
78  // parameter var info table
79  static const struct AP_Param::GroupInfo var_info[];
80 
81 private:
84 
86  uint8_t healthy : 1; // true if sensor is healthy
87  } _flags;
88 
89  // parameters
90  AP_Int8 _enabled; // enabled/disabled flag
91  AP_Int16 _flowScalerX; // X axis flow scale factor correction - parts per thousand
92  AP_Int16 _flowScalerY; // Y axis flow scale factor correction - parts per thousand
93  AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees
94  AP_Vector3f _pos_offset; // position offset of the flow sensor in the body frame
95  AP_Int8 _address; // address on the bus (allows selecting between 8 possible I2C addresses for px4flow)
96 
97  // state filled in by backend
99 
100  uint32_t _last_update_ms; // millis() time of last update
101 };
102 
103 #include "OpticalFlow_backend.h"
AP_Int16 _flowScalerY
Definition: OpticalFlow.h:92
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_Vector3f _pos_offset
Definition: OpticalFlow.h:94
AP_Int8 _enabled
Definition: OpticalFlow.h:90
uint8_t device_id() const
Definition: OpticalFlow.h:61
AP_AHRS_NavEKF & _ahrs
Definition: OpticalFlow.h:82
bool healthy() const
Definition: OpticalFlow.h:46
static const struct AP_Param::GroupInfo var_info[]
Definition: OpticalFlow.h:79
AP_Int16 _flowScalerX
Definition: OpticalFlow.h:91
const Vector2f & flowRate() const
Definition: OpticalFlow.h:55
bool enabled() const
Definition: OpticalFlow.h:43
uint32_t _last_update_ms
Definition: OpticalFlow.h:100
struct OpticalFlow::AP_OpticalFlow_Flags _flags
OpticalFlow_backend * backend
Definition: OpticalFlow.h:83
uint8_t quality() const
Definition: OpticalFlow.h:52
struct OpticalFlow_state _state
Definition: OpticalFlow.h:98
AP_Int8 _address
Definition: OpticalFlow.h:95
uint32_t last_update() const
Definition: OpticalFlow.h:64
const Vector2f & bodyRate() const
Definition: OpticalFlow.h:58
OpticalFlow(AP_AHRS_NavEKF &ahrs)
Definition: OpticalFlow.cpp:72
void init(void)
Definition: OpticalFlow.cpp:84
AP_Int16 _yawAngle_cd
Definition: OpticalFlow.h:93
void update(void)
OpticalFlow & operator=(const OpticalFlow &)=delete
const Vector3f & get_pos_offset(void) const
Definition: OpticalFlow.h:74