APM:Libraries
AP_OpticalFlow_PX4Flow.cpp
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 /*
16  driver for PX4Flow optical flow sensor
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include "AP_OpticalFlow_PX4Flow.h"
21 #include <AP_Math/edc.h>
22 #include <AP_AHRS/AP_AHRS.h>
23 #include <AP_HAL/I2CDevice.h>
24 #include <utility>
25 #include "OpticalFlow.h"
26 #include <stdio.h>
27 
28 extern const AP_HAL::HAL& hal;
29 
30 #define PX4FLOW_BASE_I2C_ADDR 0x42
31 #define PX4FLOW_INIT_RETRIES 10 // attempt to initialise the sensor up to 10 times at startup
32 
33 // constructor
35  OpticalFlow_backend(_frontend)
36 {
37 }
38 
39 
40 // detect the device
42 {
43  AP_OpticalFlow_PX4Flow *sensor = new AP_OpticalFlow_PX4Flow(_frontend);
44  if (!sensor) {
45  return nullptr;
46  }
47  if (!sensor->setup_sensor()) {
48  delete sensor;
49  return nullptr;
50  }
51  return sensor;
52 }
53 
54 /*
55  look for the sensor on different buses
56  */
58 {
59  bool success = false;
60  uint8_t retry_attempt = 0;
61 
62  while (!success && retry_attempt < PX4FLOW_INIT_RETRIES) {
63  for (uint8_t bus = 0; bus < 3; bus++) {
64  #ifdef HAL_OPTFLOW_PX4FLOW_I2C_BUS
65  // only one bus from HAL
66  if (bus != HAL_OPTFLOW_PX4FLOW_I2C_BUS) {
67  continue;
68  }
69  #endif
71  if (!tdev) {
72  continue;
73  }
75  continue;
76  }
77  struct i2c_integral_frame frame;
78  success = tdev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame));
79  tdev->get_semaphore()->give();
80  if (success) {
81  printf("Found PX4Flow on bus %u\n", bus);
82  dev = std::move(tdev);
83  break;
84  }
85  }
86  retry_attempt++;
87  if (!success) {
88  hal.scheduler->delay(10);
89  }
90  }
91  return success;
92 }
93 
94 // setup the device
96 {
97  if (!scan_buses()) {
98  return false;
99  }
100  // read at 10Hz
102  return true;
103 }
104 
105 
106 // update - read latest values from sensor and fill in x,y and totals.
108 {
109 }
110 
111 // timer to read sensor
113 {
114  struct i2c_integral_frame frame;
115  if (!dev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame))) {
116  return;
117  }
118  struct OpticalFlow::OpticalFlow_state state {};
119  state.device_id = get_address();
120 
121  if (frame.integration_timespan > 0) {
122  const Vector2f flowScaler = _flowScaler();
123  float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
124  float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;
125  float integralToRate = 1.0e6 / frame.integration_timespan;
126 
127  state.surface_quality = frame.qual;
128  state.flowRate = Vector2f(frame.pixel_flow_x_integral * flowScaleFactorX,
129  frame.pixel_flow_y_integral * flowScaleFactorY) * 1.0e-4 * integralToRate;
130  state.bodyRate = Vector2f(frame.gyro_x_rate_integral, frame.gyro_y_rate_integral) * 1.0e-4 * integralToRate;
131 
132  _applyYaw(state.flowRate);
133  _applyYaw(state.bodyRate);
134  }
135 
136  _update_frontend(state);
137 }
int printf(const char *fmt,...)
Definition: stdio.c:113
static const uint8_t REG_INTEGRAL_FRAME
Vector2< float > Vector2f
Definition: vector2.h:239
#define PX4FLOW_BASE_I2C_ADDR
void _applyYaw(Vector2f &v)
uint8_t get_address(void) const
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
Vector2f _flowScaler(void) const
virtual AP_HAL::Semaphore * get_semaphore()=0
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
static AP_OpticalFlow_PX4Flow * detect(OpticalFlow &_frontend)
AP_OpticalFlow_PX4Flow(OpticalFlow &_frontend)
constructor
virtual void delay(uint16_t ms)=0
#define HAL_OPTFLOW_PX4FLOW_I2C_BUS
Definition: linux.h:380
T y
Definition: vector2.h:37
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
virtual bool give()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
T x
Definition: vector2.h:37
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
AP_HAL::OwnPtr< AP_HAL::Device > dev
#define PX4FLOW_INIT_RETRIES
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114