PX4 Firmware
PX4 Autopilot Software http://px4.io
PAW3902.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "PAW3902.hpp"
35 
36 PAW3902::PAW3902(int bus, enum Rotation yaw_rotation) :
37  SPI("PAW3902", nullptr, bus, PAW3902_SPIDEV, SPIDEV_MODE0, PAW3902_SPI_BUS_SPEED),
38  ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
39  _sample_perf(perf_alloc(PC_ELAPSED, "paw3902: read")),
40  _comms_errors(perf_alloc(PC_COUNT, "paw3902: com_err")),
41  _dupe_count_perf(perf_alloc(PC_COUNT, "paw3902: duplicate reading")),
42  _yaw_rotation(yaw_rotation)
43 {
44 }
45 
47 {
48  // make sure we are truly inactive
49  stop();
50 
51  // free perf counters
55 }
56 
57 int
59 {
60  // get yaw rotation from sensor frame to body frame
61  param_t rot = param_find("SENS_FLOW_ROT");
62 
63  if (rot != PARAM_INVALID) {
64  int32_t val = 0;
65 
66  if (param_get(rot, &val) == PX4_OK) {
67  _yaw_rotation = (enum Rotation)val;
68  }
69  }
70 
71  /* For devices competing with NuttX SPI drivers on a bus (Crazyflie SD Card expansion board) */
72  SPI::set_lockmode(LOCK_THREADS);
73 
74  /* do SPI init (and probe) first */
75  if (SPI::init() != OK) {
76  return PX4_ERROR;
77  }
78 
79  reset();
80 
81  // default to low light mode (1)
82  modeLowLight();
83 
85 
86  start();
87 
88  return PX4_OK;
89 }
90 
91 int
93 {
94  uint8_t product_id = registerRead(Register::Product_ID);
95 
96  PX4_INFO("DEVICE_ID: %X", product_id);
97 
98  // Test the SPI communication, checking chipId and inverse chipId
99  if (product_id != PRODUCT_ID) {
100  return PX4_ERROR;
101  }
102 
103  uint8_t revision_id = registerRead(Register::Revision_ID);
104  PX4_INFO("REVISION_ID: %X", revision_id);
105 
106  if (revision_id != REVISION_ID) {
107  return PX4_ERROR;
108  }
109 
110  return PX4_OK;
111 }
112 
113 bool
115 {
116  // Power on reset
118  usleep(5000);
119 
120  // Read from registers 0x02, 0x03, 0x04, 0x05 and 0x06 one time regardless of the motion state
126 
127  usleep(1000);
128 
129  return true;
130 }
131 
132 bool
134 {
135  if (newMode != _mode) {
136  PX4_INFO("changing from mode %d -> %d", static_cast<int>(_mode), static_cast<int>(newMode));
137  ScheduleClear();
138  reset();
139 
140  switch (newMode) {
141  case Mode::Bright:
142  modeBright();
143  ScheduleOnInterval(SAMPLE_INTERVAL_MODE_0);
144  break;
145 
146  case Mode::LowLight:
147  modeLowLight();
148  ScheduleOnInterval(SAMPLE_INTERVAL_MODE_1);
149  break;
150 
151  case Mode::SuperLowLight:
153  ScheduleOnInterval(SAMPLE_INTERVAL_MODE_2);
154  break;
155  }
156 
157  _mode = newMode;
158  }
159 
160  // Approximate Resolution = (Register Value + 1) * (50 / 8450) ≈ 0.6% of data point in Figure 19
161  // The maximum register value is 0xA8. The minimum register value is 0.
162  uint8_t resolution = registerRead(Register::Resolution);
163  PX4_INFO("Resolution: %X", resolution);
164  PX4_INFO("Resolution is approx: %.3f", (double)((resolution + 1.0f) * (50.0f / 8450.0f)));
165 
166  return true;
167 }
168 
169 bool
171 {
172  // Mode 0: Bright (126 fps) 60 Lux typical
173 
174  // set performance optimization registers
175  registerWrite(0x7F, 0x00);
176  registerWrite(0x55, 0x01);
177  registerWrite(0x50, 0x07);
178  registerWrite(0x7f, 0x0e);
179  registerWrite(0x43, 0x10);
180 
181  registerWrite(0x48, 0x02);
182  registerWrite(0x7F, 0x00);
183  registerWrite(0x51, 0x7b);
184  registerWrite(0x50, 0x00);
185  registerWrite(0x55, 0x00);
186 
187  registerWrite(0x7F, 0x00);
188  registerWrite(0x61, 0xAD);
189  registerWrite(0x7F, 0x03);
190  registerWrite(0x40, 0x00);
191  registerWrite(0x7F, 0x05);
192  registerWrite(0x41, 0xB3);
193  registerWrite(0x43, 0xF1);
194  registerWrite(0x45, 0x14);
195  registerWrite(0x5F, 0x34);
196  registerWrite(0x7B, 0x08);
197  registerWrite(0x5e, 0x34);
198  registerWrite(0x5b, 0x32);
199  registerWrite(0x6d, 0x32);
200  registerWrite(0x45, 0x17);
201  registerWrite(0x70, 0xe5);
202  registerWrite(0x71, 0xe5);
203  registerWrite(0x7F, 0x06);
204  registerWrite(0x44, 0x1B);
205  registerWrite(0x40, 0xBF);
206  registerWrite(0x4E, 0x3F);
207  registerWrite(0x7F, 0x08);
208  registerWrite(0x66, 0x44);
209  registerWrite(0x65, 0x20);
210  registerWrite(0x6a, 0x3a);
211  registerWrite(0x61, 0x05);
212  registerWrite(0x62, 0x05);
213  registerWrite(0x7F, 0x09);
214  registerWrite(0x4F, 0xAF);
215  registerWrite(0x48, 0x80);
216  registerWrite(0x49, 0x80);
217  registerWrite(0x57, 0x77);
218  registerWrite(0x5F, 0x40);
219  registerWrite(0x60, 0x78);
220  registerWrite(0x61, 0x78);
221  registerWrite(0x62, 0x08);
222  registerWrite(0x63, 0x50);
223  registerWrite(0x7F, 0x0A);
224  registerWrite(0x45, 0x60);
225  registerWrite(0x7F, 0x00);
226  registerWrite(0x4D, 0x11);
227  registerWrite(0x55, 0x80);
228  registerWrite(0x74, 0x21);
229  registerWrite(0x75, 0x1F);
230  registerWrite(0x4A, 0x78);
231  registerWrite(0x4B, 0x78);
232  registerWrite(0x44, 0x08);
233  registerWrite(0x45, 0x50);
234  registerWrite(0x64, 0xFE);
235  registerWrite(0x65, 0x1F);
236  registerWrite(0x72, 0x0A);
237  registerWrite(0x73, 0x00);
238  registerWrite(0x7F, 0x14);
239  registerWrite(0x44, 0x84);
240  registerWrite(0x65, 0x47);
241  registerWrite(0x66, 0x18);
242  registerWrite(0x63, 0x70);
243  registerWrite(0x6f, 0x2c);
244  registerWrite(0x7F, 0x15);
245  registerWrite(0x48, 0x48);
246  registerWrite(0x7F, 0x07);
247  registerWrite(0x41, 0x0D);
248  registerWrite(0x43, 0x14);
249  registerWrite(0x4B, 0x0E);
250  registerWrite(0x45, 0x0F);
251  registerWrite(0x44, 0x42);
252  registerWrite(0x4C, 0x80);
253  registerWrite(0x7F, 0x10);
254  registerWrite(0x5B, 0x03);
255  registerWrite(0x7F, 0x07);
256  registerWrite(0x40, 0x41);
257 
258  usleep(10_ms); // delay 10ms
259 
260  registerWrite(0x7F, 0x00);
261  registerWrite(0x32, 0x00);
262  registerWrite(0x7F, 0x07);
263  registerWrite(0x40, 0x40);
264  registerWrite(0x7F, 0x06);
265  registerWrite(0x68, 0x70);
266  registerWrite(0x69, 0x01);
267  registerWrite(0x7F, 0x0D);
268  registerWrite(0x48, 0xC0);
269  registerWrite(0x6F, 0xD5);
270  registerWrite(0x7F, 0x00);
271  registerWrite(0x5B, 0xA0);
272  registerWrite(0x4E, 0xA8);
273  registerWrite(0x5A, 0x50);
274  registerWrite(0x40, 0x80);
275  registerWrite(0x73, 0x1f);
276 
277  usleep(10_ms); // delay 10ms
278 
279  registerWrite(0x73, 0x00);
280 
281  return false;
282 }
283 
284 bool
286 {
287  // Mode 1: Low Light (126 fps) 30 Lux typical
288  // low light and low speed motion tracking
289 
290  // set performance optimization registers
291  registerWrite(0x7F, 0x00);
292  registerWrite(0x55, 0x01);
293  registerWrite(0x50, 0x07);
294  registerWrite(0x7f, 0x0e);
295  registerWrite(0x43, 0x10);
296 
297  registerWrite(0x48, 0x02);
298  registerWrite(0x7F, 0x00);
299  registerWrite(0x51, 0x7b);
300  registerWrite(0x50, 0x00);
301  registerWrite(0x55, 0x00);
302 
303  registerWrite(0x7F, 0x00);
304  registerWrite(0x61, 0xAD);
305  registerWrite(0x7F, 0x03);
306  registerWrite(0x40, 0x00);
307  registerWrite(0x7F, 0x05);
308  registerWrite(0x41, 0xB3);
309  registerWrite(0x43, 0xF1);
310  registerWrite(0x45, 0x14);
311  registerWrite(0x5F, 0x34);
312  registerWrite(0x7B, 0x08);
313  registerWrite(0x5e, 0x34);
314  registerWrite(0x5b, 0x65);
315  registerWrite(0x6d, 0x65);
316  registerWrite(0x45, 0x17);
317  registerWrite(0x70, 0xe5);
318  registerWrite(0x71, 0xe5);
319  registerWrite(0x7F, 0x06);
320  registerWrite(0x44, 0x1B);
321  registerWrite(0x40, 0xBF);
322  registerWrite(0x4E, 0x3F);
323  registerWrite(0x7F, 0x08);
324  registerWrite(0x66, 0x44);
325  registerWrite(0x65, 0x20);
326  registerWrite(0x6a, 0x3a);
327  registerWrite(0x61, 0x05);
328  registerWrite(0x62, 0x05);
329  registerWrite(0x7F, 0x09);
330  registerWrite(0x4F, 0xAF);
331  registerWrite(0x48, 0x80);
332  registerWrite(0x49, 0x80);
333  registerWrite(0x57, 0x77);
334  registerWrite(0x5F, 0x40);
335  registerWrite(0x60, 0x78);
336  registerWrite(0x61, 0x78);
337  registerWrite(0x62, 0x08);
338  registerWrite(0x63, 0x50);
339  registerWrite(0x7F, 0x0A);
340  registerWrite(0x45, 0x60);
341  registerWrite(0x7F, 0x00);
342  registerWrite(0x4D, 0x11);
343  registerWrite(0x55, 0x80);
344  registerWrite(0x74, 0x21);
345  registerWrite(0x75, 0x1F);
346  registerWrite(0x4A, 0x78);
347  registerWrite(0x4B, 0x78);
348  registerWrite(0x44, 0x08);
349  registerWrite(0x45, 0x50);
350  registerWrite(0x64, 0xFE);
351  registerWrite(0x65, 0x1F);
352  registerWrite(0x72, 0x0A);
353  registerWrite(0x73, 0x00);
354  registerWrite(0x7F, 0x14);
355  registerWrite(0x44, 0x84);
356  registerWrite(0x65, 0x67);
357  registerWrite(0x66, 0x18);
358  registerWrite(0x63, 0x70);
359  registerWrite(0x6f, 0x2c);
360  registerWrite(0x7F, 0x15);
361  registerWrite(0x48, 0x48);
362  registerWrite(0x7F, 0x07);
363  registerWrite(0x41, 0x0D);
364  registerWrite(0x43, 0x14);
365  registerWrite(0x4B, 0x0E);
366  registerWrite(0x45, 0x0F);
367  registerWrite(0x44, 0x42);
368  registerWrite(0x4C, 0x80);
369  registerWrite(0x7F, 0x10);
370  registerWrite(0x5B, 0x03);
371  registerWrite(0x7F, 0x07);
372  registerWrite(0x40, 0x41);
373 
374  usleep(10_ms); // delay 10ms
375 
376  registerWrite(0x7F, 0x00);
377  registerWrite(0x32, 0x00);
378  registerWrite(0x7F, 0x07);
379  registerWrite(0x40, 0x40);
380  registerWrite(0x7F, 0x06);
381  registerWrite(0x68, 0x70);
382  registerWrite(0x69, 0x01);
383  registerWrite(0x7F, 0x0D);
384  registerWrite(0x48, 0xC0);
385  registerWrite(0x6F, 0xD5);
386  registerWrite(0x7F, 0x00);
387  registerWrite(0x5B, 0xA0);
388  registerWrite(0x4E, 0xA8);
389  registerWrite(0x5A, 0x50);
390  registerWrite(0x40, 0x80);
391  registerWrite(0x73, 0x1f);
392 
393  usleep(10_ms); // delay 10ms
394 
395  registerWrite(0x73, 0x00);
396 
397  return false;
398 }
399 
400 bool
402 {
403  // Mode 2: Super Low Light (50 fps) 9 Lux typical
404  // super low light and low speed motion tracking
405 
406  // set performance optimization registers
407  registerWrite(0x7F, 0x00);
408  registerWrite(0x55, 0x01);
409  registerWrite(0x50, 0x07);
410  registerWrite(0x7f, 0x0e);
411  registerWrite(0x43, 0x10);
412 
413  registerWrite(0x48, 0x04);
414  registerWrite(0x7F, 0x00);
415  registerWrite(0x51, 0x7b);
416  registerWrite(0x50, 0x00);
417  registerWrite(0x55, 0x00);
418 
419  registerWrite(0x7F, 0x00);
420  registerWrite(0x61, 0xAD);
421  registerWrite(0x7F, 0x03);
422  registerWrite(0x40, 0x00);
423  registerWrite(0x7F, 0x05);
424  registerWrite(0x41, 0xB3);
425  registerWrite(0x43, 0xF1);
426  registerWrite(0x45, 0x14);
427  registerWrite(0x5F, 0x34);
428  registerWrite(0x7B, 0x08);
429  registerWrite(0x5E, 0x34);
430  registerWrite(0x5B, 0x32);
431  registerWrite(0x6D, 0x32);
432  registerWrite(0x45, 0x17);
433  registerWrite(0x70, 0xE5);
434  registerWrite(0x71, 0xE5);
435  registerWrite(0x7F, 0x06);
436  registerWrite(0x44, 0x1B);
437  registerWrite(0x40, 0xBF);
438  registerWrite(0x4E, 0x3F);
439  registerWrite(0x7F, 0x08);
440  registerWrite(0x66, 0x44);
441  registerWrite(0x65, 0x20);
442  registerWrite(0x6A, 0x3a);
443  registerWrite(0x61, 0x05);
444  registerWrite(0x62, 0x05);
445  registerWrite(0x7F, 0x09);
446  registerWrite(0x4F, 0xAF);
447  registerWrite(0x48, 0x80);
448  registerWrite(0x49, 0x80);
449  registerWrite(0x57, 0x77);
450  registerWrite(0x5F, 0x40);
451  registerWrite(0x60, 0x78);
452  registerWrite(0x61, 0x78);
453  registerWrite(0x62, 0x08);
454  registerWrite(0x63, 0x50);
455  registerWrite(0x7F, 0x0A);
456  registerWrite(0x45, 0x60);
457  registerWrite(0x7F, 0x00);
458  registerWrite(0x4D, 0x11);
459  registerWrite(0x55, 0x80);
460  registerWrite(0x74, 0x21);
461  registerWrite(0x75, 0x1F);
462  registerWrite(0x4A, 0x78);
463  registerWrite(0x4B, 0x78);
464  registerWrite(0x44, 0x08);
465  registerWrite(0x45, 0x50);
466  registerWrite(0x64, 0xCE);
467  registerWrite(0x65, 0x0B);
468  registerWrite(0x72, 0x0A);
469  registerWrite(0x73, 0x00);
470  registerWrite(0x7F, 0x14);
471  registerWrite(0x44, 0x84);
472  registerWrite(0x65, 0x67);
473  registerWrite(0x66, 0x18);
474  registerWrite(0x63, 0x70);
475  registerWrite(0x6f, 0x2c);
476  registerWrite(0x7F, 0x15);
477  registerWrite(0x48, 0x48);
478  registerWrite(0x7F, 0x07);
479  registerWrite(0x41, 0x0D);
480  registerWrite(0x43, 0x14);
481  registerWrite(0x4B, 0x0E);
482  registerWrite(0x45, 0x0F);
483  registerWrite(0x44, 0x42);
484  registerWrite(0x4C, 0x80);
485  registerWrite(0x7F, 0x10);
486  registerWrite(0x5B, 0x02);
487  registerWrite(0x7F, 0x07);
488  registerWrite(0x40, 0x41);
489 
490  usleep(25_ms); // delay 25ms
491 
492  registerWrite(0x7F, 0x00);
493  registerWrite(0x32, 0x44);
494  registerWrite(0x7F, 0x07);
495  registerWrite(0x40, 0x40);
496  registerWrite(0x7F, 0x06);
497  registerWrite(0x68, 0x40);
498  registerWrite(0x69, 0x02);
499  registerWrite(0x7F, 0x0D);
500  registerWrite(0x48, 0xC0);
501  registerWrite(0x6F, 0xD5);
502  registerWrite(0x7F, 0x00);
503  registerWrite(0x5B, 0xA0);
504  registerWrite(0x4E, 0xA8);
505  registerWrite(0x5A, 0x50);
506  registerWrite(0x40, 0x80);
507  registerWrite(0x73, 0x0B);
508 
509  usleep(25_ms); // delay 25ms
510 
511  registerWrite(0x73, 0x00);
512 
513  return true;
514 }
515 
516 uint8_t
518 {
519  uint8_t cmd[2] {};
520  cmd[0] = reg;
521  transfer(&cmd[0], &cmd[0], sizeof(cmd));
522  up_udelay(T_SRR);
523  return cmd[1];
524 }
525 
526 void
527 PAW3902::registerWrite(uint8_t reg, uint8_t data)
528 {
529  uint8_t cmd[2];
530  cmd[0] = DIR_WRITE(reg);
531  cmd[1] = data;
532  transfer(&cmd[0], nullptr, sizeof(cmd));
533  up_udelay(T_SWW);
534 }
535 
536 void
538 {
540 
541  struct TransferBuffer {
542  uint8_t cmd = Register::Motion_Burst;
544  };
545  TransferBuffer buf;
546  static_assert(sizeof(buf) == (12 + 1));
547 
548  const hrt_abstime timestamp_sample = hrt_absolute_time();
549 
550  if (transfer((uint8_t *)&buf, (uint8_t *)&buf, sizeof(buf)) != PX4_OK) {
553  return;
554  }
555 
556  const uint64_t dt_flow = timestamp_sample - _previous_collect_timestamp;
557  _flow_dt_sum_usec += dt_flow;
559 
560  // update for next iteration
561  _previous_collect_timestamp = timestamp_sample;
562 
563  // PX4_INFO("data.Motion %d", buf.data.Motion);
564  // PX4_INFO("data.Observation %d", buf.data.Observation);
565  // PX4_INFO("data.Delta_X_L %d", buf.data.Delta_X_L);
566  // PX4_INFO("data.Delta_X_H %d", buf.data.Delta_X_H);
567  // PX4_INFO("data.Delta_Y_L %d", buf.data.Delta_Y_L);
568  // PX4_INFO("data.Delta_Y_H %d", buf.data.Delta_Y_H);
569  // PX4_INFO("data.SQUAL %d", buf.data.SQUAL);
570  // PX4_INFO("data.RawData_Sum %d", buf.data.RawData_Sum);
571  // PX4_INFO("data.Maximum_RawData %d", buf.data.Maximum_RawData);
572  // PX4_INFO("data.Minimum_RawData %d", buf.data.Minimum_RawData);
573  // PX4_INFO("data.Shutter_Upper %d", buf.data.Shutter_Upper);
574  // PX4_INFO("data.Shutter_Lower %d", buf.data.Shutter_Lower);
575 
576  const int16_t delta_x_raw = ((int16_t)buf.data.Delta_X_H << 8) | buf.data.Delta_X_L;
577  const int16_t delta_y_raw = ((int16_t)buf.data.Delta_Y_H << 8) | buf.data.Delta_Y_L;
578 
579  // check SQUAL & Shutter values
580  // To suppress false motion reports, discard Delta X and Delta Y values if the SQUAL and Shutter values meet the condition
581  // Bright Mode, SQUAL < 0x19, Shutter ≥ 0x1FF0
582  // Low Light Mode, SQUAL < 0x46, Shutter ≥ 0x1FF0
583  // Super Low Light Mode, SQUAL < 0x55, Shutter ≥ 0x0BC0
584  const uint16_t shutter = (buf.data.Shutter_Upper << 8) | buf.data.Shutter_Lower;
585 
586  if ((buf.data.SQUAL < 0x19) && (shutter >= 0x0BC0)) {
587  PX4_ERR("false motion report, discarding");
589  return;
590  }
591 
592  switch (_mode) {
593  case Mode::Bright:
594  if ((shutter >= 0x1FFE) && (buf.data.RawData_Sum < 0x3C)) { // AND valid for 10 consecutive frames?
595  // Bright -> LowLight
596  changeMode(Mode::LowLight);
597  }
598 
599  break;
600 
601  case Mode::LowLight:
602  if ((shutter >= 0x1FFE) && (buf.data.RawData_Sum < 0x5A)) { // AND valid for 10 consecutive frames?
603  // LowLight -> SuperLowLight
604  changeMode(Mode::SuperLowLight);
605 
606  } else if ((shutter >= 0x0BB8)) { // AND valid for 10 consecutive frames?
607  // LowLight -> Bright
608  changeMode(Mode::Bright);
609  }
610 
611  break;
612 
613  case Mode::SuperLowLight:
614 
615  // SuperLowLight -> LowLight
616  if ((shutter >= 0x03E8)) { // AND valid for 10 consecutive frames?
617  changeMode(Mode::LowLight);
618  }
619 
620  // PAW3902JF should not operate with Shutter < 0x01F4 in Mode 2
621  if (shutter >= 0x01F4) {
622  changeMode(Mode::LowLight);
623  }
624 
625  break;
626  }
627 
628  // TODO: page 35 switching scheme
629 
630  // As a minimum requirement, PAW3902JF should not operate with Shutter < 0x01F4 in Mode 2, and must switch to the next operation mode.
631 
632  _flow_sum_x += delta_x_raw;
633  _flow_sum_y += delta_y_raw;
634 
635  // returns if the collect time has not been reached
638  return;
639  }
640 
641  optical_flow_s report{};
642  report.timestamp = timestamp_sample;
643 
644 
645  //PX4_INFO("X: %d Y: %d", _flow_sum_x, _flow_sum_y);
646 
647  report.pixel_flow_x_integral = (float)_flow_sum_x / 500.0f; // proportional factor + convert from pixels to radians
648  report.pixel_flow_y_integral = (float)_flow_sum_y / 500.0f; // proportional factor + convert from pixels to radians
649 
650  // rotate measurements in yaw from sensor frame to body frame according to parameter SENS_FLOW_ROT
651  float zeroval = 0.0f;
652  rotate_3f(_yaw_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval);
653 
654  report.frame_count_since_last_readout = _frame_count_since_last;
655  report.integration_timespan = _flow_dt_sum_usec; // microseconds
656 
657  report.sensor_id = 0;
658  report.quality = buf.data.SQUAL;
659 
660  /* No gyro on this board */
661  report.gyro_x_rate_integral = NAN;
662  report.gyro_y_rate_integral = NAN;
663  report.gyro_z_rate_integral = NAN;
664 
665  // set (conservative) specs according to datasheet
666  report.max_flow_rate = 5.0f; // Datasheet: 7.4 rad/s
667  report.min_ground_distance = 0.08f; // Datasheet: 80mm
668  report.max_ground_distance = 30.0f; // Datasheet: infinity
669 
670  _optical_flow_pub.publish(report);
671 
672  // reset
673  _flow_dt_sum_usec = 0;
674  _flow_sum_x = 0;
675  _flow_sum_y = 0;
677 
679 }
680 
681 void
683 {
684  // schedule a cycle to start things
685  ScheduleOnInterval(SAMPLE_INTERVAL_MODE_1);
686 }
687 
688 void
690 {
691  ScheduleClear();
692 }
693 
694 void
696 {
700 }
#define PARAM_INVALID
Handle returned when a parameter cannot be found.
Definition: param.h:103
static constexpr uint64_t T_SRR
uint64_t _previous_collect_timestamp
Definition: PAW3902.hpp:128
void registerWrite(uint8_t reg, uint8_t data)
Definition: PAW3902.cpp:527
void stop()
Definition: PAW3902.cpp:689
static constexpr uint64_t T_SWW
static constexpr uint32_t SAMPLE_INTERVAL_MODE_2
measure the time elapsed performing an event
Definition: perf_counter.h:56
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
Definition: parameters.cpp:589
perf_counter_t _sample_perf
Definition: PAW3902.hpp:122
uint64_t timestamp
Definition: optical_flow.h:53
void print_info()
Definition: PAW3902.cpp:695
void Run() override
Definition: PAW3902.cpp:537
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
Definition: rotation.cpp:63
static constexpr uint32_t SAMPLE_INTERVAL_MODE_0
static constexpr uint32_t SAMPLE_INTERVAL_MODE_1
bool reset()
Definition: PAW3902.cpp:114
uint64_t _flow_dt_sum_usec
Definition: PAW3902.hpp:129
bool modeLowLight()
Definition: PAW3902.cpp:285
perf_counter_t _comms_errors
Definition: PAW3902.hpp:123
bool changeMode(Mode newMode)
Definition: PAW3902.cpp:133
count the number of times an event occurs
Definition: perf_counter.h:55
uORB::PublicationMulti< optical_flow_s > _optical_flow_pub
Definition: PAW3902.hpp:120
bool modeBright()
Definition: PAW3902.cpp:170
perf_counter_t _dupe_count_perf
Definition: PAW3902.hpp:124
virtual ~PAW3902()
Definition: PAW3902.cpp:46
#define PAW3902_SPI_BUS_SPEED
Definition: PAW3902.hpp:79
void perf_count(perf_counter_t handle)
Count a performance event.
void perf_free(perf_counter_t handle)
Free a counter.
int _flow_sum_y
Definition: PAW3902.hpp:135
void init()
Activates/configures the hardware registers.
#define perf_alloc(a, b)
Definition: px4io.h:59
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
int _flow_sum_x
Definition: PAW3902.hpp:134
uint8_t * data
Definition: dataman.cpp:149
unsigned _frame_count_since_last
Definition: PAW3902.hpp:130
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
Mode _mode
Definition: PAW3902.hpp:137
void perf_end(perf_counter_t handle)
End a performance event.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
Definition: parameters.cpp:370
#define DIR_WRITE
Definition: bmp388_spi.cpp:47
PAW3902(int bus=PAW3902_BUS, enum Rotation yaw_rotation=ROTATION_NONE)
Definition: PAW3902.cpp:36
void start()
Definition: PAW3902.cpp:682
bool modeSuperLowLight()
Definition: PAW3902.cpp:401
static constexpr uint8_t PRODUCT_ID
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
Definition: bst.cpp:62
virtual int probe()
Definition: PAW3902.cpp:92
#define OK
Definition: uavcan_main.cpp:71
virtual int init()
Definition: PAW3902.cpp:58
bool publish(const T &data)
Publish the struct.
uint8_t registerRead(uint8_t reg)
Definition: PAW3902.cpp:517
static constexpr uint64_t _collect_time
Definition: PAW3902.hpp:126
void perf_begin(perf_counter_t handle)
Begin a performance event.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
uint32_t param_t
Parameter handle.
Definition: param.h:98
static constexpr uint8_t REVISION_ID