PX4 Firmware
PX4 Autopilot Software http://px4.io
PAW3902.hpp
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 /**
35  * @file paw3902.cpp
36  *
37  * Driver for the Pixart PAW3902 optical flow sensor connected via SPI.
38  */
39 
40 #pragma once
41 
43 
44 #include <px4_platform_common/px4_config.h>
45 #include <px4_platform_common/defines.h>
46 #include <px4_platform_common/getopt.h>
47 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
48 #include <drivers/device/spi.h>
49 #include <conversion/rotation.h>
50 #include <lib/perf/perf_counter.h>
51 #include <lib/parameters/param.h>
52 #include <drivers/drv_hrt.h>
56 
57 /* Configuration Constants */
58 
59 #if defined PX4_SPI_BUS_EXPANSION // crazyflie
60 # define PAW3902_BUS PX4_SPI_BUS_EXPANSION
61 #elif defined PX4_SPI_BUS_EXTERNAL1 // fmu-v5
62 # define PAW3902_BUS PX4_SPI_BUS_EXTERNAL1
63 #elif defined PX4_SPI_BUS_EXTERNAL // fmu-v4 extspi
64 # define PAW3902_BUS PX4_SPI_BUS_EXTERNAL
65 #else
66 # error "add the required spi bus from board_config.h here"
67 #endif
68 
69 #if defined PX4_SPIDEV_EXPANSION_2 // crazyflie flow deck
70 # define PAW3902_SPIDEV PX4_SPIDEV_EXPANSION_2
71 #elif defined PX4_SPIDEV_EXTERNAL1_1 // fmu-v5 ext CS1
72 # define PAW3902_SPIDEV PX4_SPIDEV_EXTERNAL1_1
73 #elif defined PX4_SPIDEV_EXTERNAL // fmu-v4 extspi
74 # define PAW3902_SPIDEV PX4_SPIDEV_EXTERNAL
75 #else
76 # error "add the required spi dev from board_config.h here"
77 #endif
78 
79 #define PAW3902_SPI_BUS_SPEED (2000000L) // 2MHz
80 
81 #define DIR_WRITE(a) ((a) | (1 << 7))
82 #define DIR_READ(a) ((a) & 0x7f)
83 
84 using namespace time_literals;
85 using namespace PixArt_PAW3902JF;
86 
87 // PAW3902JF-TXQT is PixArt Imaging
88 
89 class PAW3902 : public device::SPI, public px4::ScheduledWorkItem
90 {
91 public:
92  PAW3902(int bus = PAW3902_BUS, enum Rotation yaw_rotation = ROTATION_NONE);
93  virtual ~PAW3902();
94 
95  virtual int init();
96 
97  void print_info();
98 
99  void start();
100  void stop();
101 
102 protected:
103  virtual int probe();
104 
105 private:
106 
107  void Run() override;
108 
109  uint8_t registerRead(uint8_t reg);
110  void registerWrite(uint8_t reg, uint8_t data);
111 
112  bool reset();
113 
114  bool modeBright();
115  bool modeLowLight();
116  bool modeSuperLowLight();
117 
118  bool changeMode(Mode newMode);
119 
120  uORB::PublicationMulti<optical_flow_s> _optical_flow_pub{ORB_ID(optical_flow)};
121 
125 
126  static constexpr uint64_t _collect_time{15000}; // 15 milliseconds, optical flow data publish rate
127 
128  uint64_t _previous_collect_timestamp{0};
129  uint64_t _flow_dt_sum_usec{0};
130  unsigned _frame_count_since_last{0};
131 
132  enum Rotation _yaw_rotation {ROTATION_NONE};
133 
134  int _flow_sum_x{0};
135  int _flow_sum_y{0};
136 
137  Mode _mode{Mode::LowLight};
138 
139 };
perf_counter_t _sample_perf
Definition: PAW3902.hpp:122
static Mode _mode
Definition: motor_ramp.cpp:81
perf_counter_t _comms_errors
Definition: PAW3902.hpp:123
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static void stop()
Definition: dataman.cpp:1491
Vector rotation library.
High-resolution timer with callouts and timekeeping.
Global flash based parameter store.
perf_counter_t _dupe_count_perf
Definition: PAW3902.hpp:124
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Header common to all counters.
void init()
Activates/configures the hardware registers.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
static int start()
Definition: dataman.cpp:1452
Performance measuring tools.