Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
opticflow_pmw3901.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) Tom van Dijk
3  *
4  * This file is part of paparazzi
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, see
18  * <http://www.gnu.org/licenses/>.
19  */
27 
28 #include "subsystems/abi.h"
30 #include "generated/modules.h"
31 
32 #include "state.h"
33 
34 #include "std.h"
35 
36 #include <math.h>
37 
38 
39 #ifndef OPTICFLOW_PMW3901_SENSOR_ANGLE
40 #define OPTICFLOW_PMW3901_SENSOR_ANGLE 270 // [deg] Sensor rotation around body z axis (down). 0 rad = sensor x forward, y right.
41 #endif
42 
43 #ifndef OPTICFLOW_PMW3901_SUBPIXEL_FACTOR
44 #define OPTICFLOW_PMW3901_SUBPIXEL_FACTOR 100
45 #endif
46 
47 #ifndef OPTICFLOW_PMW3901_STD_PX
48 #define OPTICFLOW_PMW3901_STD_PX 50 // [px] standard deviation of flow measurement
49 #endif
50 
51 #ifndef OPTICFLOW_PMW3901_AGL_ID
52 #define OPTICFLOW_PMW3901_AGL_ID ABI_BROADCAST
53 #endif
54 PRINT_CONFIG_VAR(OPTICFLOW_PMW3901_AGL_ID)
55 
56 #ifndef OPTICFLOW_PMW3901_AGL_TIMEOUT_US
57 #define OPTICFLOW_PMW3901_AGL_TIMEOUT_US 500000
58 #endif
59 
60 
62 
64 static float agl_dist;
66 
67 
68 static void agl_cb(uint8_t sender_id, uint32_t stamp, float distance) {
69  (void) sender_id;
70  agl_dist = distance;
71  agl_ts = stamp;
72 }
73 
74 static bool agl_valid(uint32_t at_ts) {
75  return \
76  ((at_ts - agl_ts) < of_pmw.agl_timeout) &&
77  (agl_dist > 0.080);
78 }
79 
80 
81 static void opticflow_pmw3901_publish(int16_t delta_x, int16_t delta_y, uint32_t ts_usec) {
82  /* Prepare message variables */
83  // Time
84  static uint32_t prev_ts_usec = 0;
85  float dt = (ts_usec - prev_ts_usec) / 1.0e6;
86  if (prev_ts_usec == 0) {
87  dt = OPTICFLOW_PMW3901_PERIODIC_PERIOD;
88  }
89  prev_ts_usec = ts_usec;
90  // Sensor orientation
91  float c = cosf(RadOfDeg(of_pmw.sensor_angle));
92  float s = sinf(RadOfDeg(of_pmw.sensor_angle));
93  // Flow [px/s] (body-frame)
94  float flow_x = (c * delta_x - s * delta_y) / dt;
95  float flow_y = (s * delta_x + c * delta_y) / dt;
96  int16_t flow_x_subpix = (int16_t)(of_pmw.subpixel_factor * flow_x);
97  int16_t flow_y_subpix = (int16_t)(of_pmw.subpixel_factor * flow_y);
98  // Derotated flow [px/s] (body-frame)
99  struct FloatRates *rates = stateGetBodyRates_f();
100  float flow_dy_p = rates->p / of_pmw.pmw.rad_per_px;
101  float flow_dx_q = -rates->q / of_pmw.pmw.rad_per_px;
102  float flow_der_x = flow_x - flow_dx_q;
103  float flow_der_y = flow_y - flow_dy_p;
104  int16_t flow_der_x_subpix = (int16_t)(of_pmw.subpixel_factor * flow_der_x);
105  int16_t flow_der_y_subpix = (int16_t)(of_pmw.subpixel_factor * flow_der_y);
106  // Velocity
107  static float vel_x = 0; // static: keep last measurement for telemetry if agl not valid
108  static float vel_y = 0;
109  static float noise = 0;
110  if (agl_valid(ts_usec)) {
111  vel_x = -flow_der_x * of_pmw.pmw.rad_per_px * agl_dist;
112  vel_y = -flow_der_y * of_pmw.pmw.rad_per_px * agl_dist;
114  }
115 
116  /* Send ABI messages */
117  // Note: INS only subscribes to VELOCITY_ESTIMATE. OPTICAL_FLOW is only used
118  // for niche applications(?) and therefore only uses (sub)pixels without any
119  // camera intrinsics?? On the bright side, the sensor datasheet does not
120  // provide any intrinsics either.....
121  AbiSendMsgOPTICAL_FLOW(FLOW_OPTICFLOW_PMW3901_ID,
122  ts_usec, /* stamp [us] */
123  flow_x_subpix, /* flow_x [subpixels] */
124  flow_y_subpix, /* flow_y [subpixels] */
125  flow_der_x_subpix, /* flow_der_x [subpixels] */
126  flow_der_y_subpix, /* flow_der_y [subpixels] */
127  0.f, /* quality [???] */
128  0.f /* size_divergence [1/s] */
129  );
130  if (agl_valid(ts_usec)) {
131  AbiSendMsgVELOCITY_ESTIMATE(VEL_OPTICFLOW_PMW3901_ID,
132  ts_usec, /* stamp [us] */
133  vel_x, /* x [m/s] */
134  vel_y, /* y [m/s] */
135  0.f, /* z [m/s] */
136  noise, /* noise_x [m/s] */
137  noise, /* noise_y [m/s] */
138  -1.f /* noise_z [disabled] */
139  );
140  }
141 
142  /* Send telemetry */
143 #if SENSOR_SYNC_SEND_OPTICFLOW_PMW3901
144  float dummy_f = 0.f;
145  uint16_t dummy_u16 = 0;
146  uint8_t dummy_u8 = 0;
147  float fps = 1.f / dt;
148  DOWNLINK_SEND_OPTIC_FLOW_EST(DefaultChannel, DefaultDevice,
149  &fps, /* fps */
150  &dummy_u16, /* corner_cnt */
151  &dummy_u16, /* tracked_cnt */
152  &flow_x_subpix, /* flow_x */
153  &flow_y_subpix, /* flow_y */
154  &flow_der_x_subpix, /* flow_der_x */
155  &flow_der_y_subpix, /* flow_der_y */
156  &vel_x, /* vel_x */
157  &vel_y, /* vel_y */
158  &dummy_f, /* vel_z */
159  &dummy_f, /* div_size */
160  &dummy_f, /* surface_roughness */
161  &dummy_f, /* divergence */
162  &dummy_u8 /* camera_id */
163  );
164 #endif
165 }
166 
167 
169  pmw3901_init(&of_pmw.pmw, &OPTICFLOW_PMW3901_SPI_DEV, OPTICFLOW_PMW3901_SPI_SLAVE_IDX);
170  AbiBindMsgAGL(OPTICFLOW_PMW3901_AGL_ID, &agl_ev, agl_cb);
175 #ifdef OPTICFLOW_PMW3901_RAD_PER_PX
176  of_pmw.pmw.rad_per_px = OPTICFLOW_PMW3901_RAD_PER_PX;
177 #endif
178 }
179 
181  if (pmw3901_is_idle(&of_pmw.pmw)) {
183  }
184 }
185 
189  int16_t delta_x, delta_y;
190  pmw3901_get_data(&of_pmw.pmw, &delta_x, &delta_y);
191  opticflow_pmw3901_publish(delta_x, delta_y, get_sys_time_usec());
192  }
193 }
194 
195 
opticflow_pmw3901_t::agl_timeout
uint32_t agl_timeout
Definition: opticflow_pmw3901.h:36
c
VIC slots used for the LPC2148 define name e g gps UART1_VIC_SLOT e g modem SPI1_VIC_SLOT SPI1 in mcu_periph spi_arch c or spi_slave_hs_arch c(and some others not using the SPI peripheral yet..) I2C0_VIC_SLOT 8 mcu_periph/i2c_arch.c I2C1_VIC_SLOT 9 mcu_periph/i2c_arch.c USB_VIC_SLOT 10 usb
agl_ev
abi_event agl_ev
Definition: opticflow_pmw3901.c:63
uint16_t
unsigned short uint16_t
Definition: types.h:16
opticflow_pmw3901_t::std_px
float std_px
Definition: opticflow_pmw3901.h:35
VEL_OPTICFLOW_PMW3901_ID
#define VEL_OPTICFLOW_PMW3901_ID
Definition: abi_sender_ids.h:406
agl_valid
static bool agl_valid(uint32_t at_ts)
Definition: opticflow_pmw3901.c:74
abi.h
agl_ts
static uint32_t agl_ts
Definition: opticflow_pmw3901.c:65
s
static uint32_t s
Definition: light_scheduler.c:33
abi_struct
Event structure to store callbacks in a linked list.
Definition: abi_common.h:65
stateGetBodyRates_f
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition: state.h:1200
uint32_t
unsigned long uint32_t
Definition: types.h:18
opticflow_pmw3901_t
Definition: opticflow_pmw3901.h:31
pmw3901_get_data
bool pmw3901_get_data(struct pmw3901_t *pmw, int16_t *delta_x, int16_t *delta_y)
Definition: pmw3901.c:326
get_sys_time_usec
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.c:68
std.h
pmw3901_data_available
bool pmw3901_data_available(struct pmw3901_t *pmw)
Definition: pmw3901.c:322
agl_dist
static float agl_dist
Definition: opticflow_pmw3901.c:64
pmw3901_is_idle
bool pmw3901_is_idle(struct pmw3901_t *pmw)
Definition: pmw3901.c:312
int16_t
signed short int16_t
Definition: types.h:17
opticflow_pmw3901_t::subpixel_factor
int16_t subpixel_factor
Definition: opticflow_pmw3901.h:34
uint8_t
unsigned char uint8_t
Definition: types.h:14
pmw3901_start_read
void pmw3901_start_read(struct pmw3901_t *pmw)
Definition: pmw3901.c:316
FLOW_OPTICFLOW_PMW3901_ID
#define FLOW_OPTICFLOW_PMW3901_ID
Definition: abi_sender_ids.h:371
pmw3901_event
void pmw3901_event(struct pmw3901_t *pmw)
Definition: pmw3901.c:274
OPTICFLOW_PMW3901_SUBPIXEL_FACTOR
#define OPTICFLOW_PMW3901_SUBPIXEL_FACTOR
Definition: opticflow_pmw3901.c:44
f
uint16_t f
Camera baseline, in meters (i.e. horizontal distance between the two cameras of the stereo setup)
Definition: wedgebug.c:204
FloatRates::q
float q
in rad/s
Definition: pprz_algebra_float.h:95
pmw3901_init
void pmw3901_init(struct pmw3901_t *pmw, struct spi_periph *periph, uint8_t slave_idx)
Definition: pmw3901.c:249
OPTICFLOW_PMW3901_AGL_ID
#define OPTICFLOW_PMW3901_AGL_ID
Definition: opticflow_pmw3901.c:52
opticflow_pmw3901_event
void opticflow_pmw3901_event(void)
Definition: opticflow_pmw3901.c:186
opticflow_pmw3901_periodic
void opticflow_pmw3901_periodic(void)
Definition: opticflow_pmw3901.c:180
pmw3901_t::rad_per_px
float rad_per_px
Definition: pmw3901.h:71
opticflow_pmw3901_publish
static void opticflow_pmw3901_publish(int16_t delta_x, int16_t delta_y, uint32_t ts_usec)
Definition: opticflow_pmw3901.c:81
state.h
opticflow_pmw3901_t::pmw
struct pmw3901_t pmw
Definition: opticflow_pmw3901.h:32
opticflow_pmw3901_t::sensor_angle
float sensor_angle
Definition: opticflow_pmw3901.h:33
of_pmw
struct opticflow_pmw3901_t of_pmw
Definition: opticflow_pmw3901.c:61
OPTICFLOW_PMW3901_AGL_TIMEOUT_US
#define OPTICFLOW_PMW3901_AGL_TIMEOUT_US
Definition: opticflow_pmw3901.c:57
FloatRates::p
float p
in rad/s
Definition: pprz_algebra_float.h:94
OPTICFLOW_PMW3901_STD_PX
#define OPTICFLOW_PMW3901_STD_PX
Definition: opticflow_pmw3901.c:48
OPTICFLOW_PMW3901_SENSOR_ANGLE
#define OPTICFLOW_PMW3901_SENSOR_ANGLE
Definition: opticflow_pmw3901.c:40
FloatRates
angular rates
Definition: pprz_algebra_float.h:93
opticflow_pmw3901.h
agl_cb
static void agl_cb(uint8_t sender_id, uint32_t stamp, float distance)
Definition: opticflow_pmw3901.c:68
opticflow_pmw3901_init
void opticflow_pmw3901_init(void)
Definition: opticflow_pmw3901.c:168