APM:Libraries
OpticalFlow.cpp
Go to the documentation of this file.
2 #include "OpticalFlow.h"
4 #include "AP_OpticalFlow_SITL.h"
7 
8 extern const AP_HAL::HAL& hal;
9 
11  // @Param: _ENABLE
12  // @DisplayName: Optical flow enable/disable
13  // @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow
14  // @Values: 0:Disabled, 1:Enabled
15  // @User: Standard
16  AP_GROUPINFO("_ENABLE", 0, OpticalFlow, _enabled, 0),
17 
18  // @Param: _FXSCALER
19  // @DisplayName: X axis optical flow scale factor correction
20  // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor X axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the X axis optical flow reading by 0.1%. Negative values reduce the scale factor.
21  // @Range: -200 +200
22  // @Increment: 1
23  // @User: Standard
24  AP_GROUPINFO("_FXSCALER", 1, OpticalFlow, _flowScalerX, 0),
25 
26  // @Param: _FYSCALER
27  // @DisplayName: Y axis optical flow scale factor correction
28  // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor Y axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the Y axis optical flow reading by 0.1%. Negative values reduce the scale factor.
29  // @Range: -200 +200
30  // @Increment: 1
31  // @User: Standard
32  AP_GROUPINFO("_FYSCALER", 2, OpticalFlow, _flowScalerY, 0),
33 
34  // @Param: _ORIENT_YAW
35  // @DisplayName: Flow sensor yaw alignment
36  // @Description: Specifies the number of centi-degrees that the flow sensor is yawed relative to the vehicle. A sensor with its X-axis pointing to the right of the vehicle X axis has a positive yaw angle.
37  // @Range: -18000 +18000
38  // @Increment: 1
39  // @User: Standard
40  AP_GROUPINFO("_ORIENT_YAW", 3, OpticalFlow, _yawAngle_cd, 0),
41 
42  // @Param: _POS_X
43  // @DisplayName: X position offset
44  // @Description: X position of the optical flow sensor focal point in body frame. Positive X is forward of the origin.
45  // @Units: m
46  // @User: Advanced
47 
48  // @Param: _POS_Y
49  // @DisplayName: Y position offset
50  // @Description: Y position of the optical flow sensor focal point in body frame. Positive Y is to the right of the origin.
51  // @Units: m
52  // @User: Advanced
53 
54  // @Param: _POS_Z
55  // @DisplayName: Z position offset
56  // @Description: Z position of the optical flow sensor focal point in body frame. Positive Z is down from the origin.
57  // @Units: m
58  // @User: Advanced
59  AP_GROUPINFO("_POS", 4, OpticalFlow, _pos_offset, 0.0f),
60 
61  // @Param: _ADDR
62  // @DisplayName: Address on the bus
63  // @Description: This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus.
64  // @Range: 0 127
65  // @User: Advanced
66  AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0),
67 
69 };
70 
71 // default constructor
73  : _ahrs(ahrs),
74  _last_update_ms(0)
75 {
77 
78  memset(&_state, 0, sizeof(_state));
79 
80  // healthy flag will be overwritten on update
81  _flags.healthy = false;
82 }
83 
85 {
86  // return immediately if not enabled
87  if (!_enabled) {
88  return;
89  }
90 
91  if (!backend) {
92 #if AP_FEATURE_BOARD_DETECT
96  // possibly have pixhart on external SPI
97  backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this);
98  }
100  backend = AP_OpticalFlow_Pixart::detect("pixartPC15", *this);
101  }
102  if (backend == nullptr) {
104  }
105 #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
106  backend = new AP_OpticalFlow_SITL(*this);
107 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP ||\
108  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
109  backend = new AP_OpticalFlow_Onboard(*this);
110 #elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
112 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
113  backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this);
114 #endif
115  }
116 
117  if (backend != nullptr) {
118  backend->init();
119  }
120 }
121 
123 {
124  if (backend != nullptr) {
125  backend->update();
126  }
127  // only healthy if the data is less than 0.5s old
129 }
130 
static enum px4_board_type get_board_type(void)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Int8 _enabled
Definition: OpticalFlow.h:90
static const struct AP_Param::GroupInfo var_info[]
Definition: OpticalFlow.h:79
static AP_OpticalFlow_PX4Flow * detect(OpticalFlow &_frontend)
uint32_t _last_update_ms
Definition: OpticalFlow.h:100
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
struct OpticalFlow::AP_OpticalFlow_Flags _flags
#define f(i)
OpticalFlow_backend * backend
Definition: OpticalFlow.h:83
uint32_t millis()
Definition: system.cpp:157
struct OpticalFlow_state _state
Definition: OpticalFlow.h:98
OpticalFlow(AP_AHRS_NavEKF &ahrs)
Definition: OpticalFlow.cpp:72
virtual void init()=0
static AP_OpticalFlow_Pixart * detect(const char *devname, OpticalFlow &_frontend)
void init(void)
Definition: OpticalFlow.cpp:84
void update(void)
virtual void update()=0
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214