PX4 Firmware
PX4 Autopilot Software http://px4.io
PMW3901.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018-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 PMW3901.hpp
36  * @author Daniele Pettenuzzo
37  *
38  * Driver for the pmw3901 optical flow sensor connected via SPI.
39  */
40 
41 #include <px4_platform_common/px4_config.h>
42 #include <px4_platform_common/defines.h>
43 #include <px4_platform_common/getopt.h>
44 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
45 #include <drivers/device/spi.h>
46 #include <conversion/rotation.h>
47 #include <lib/perf/perf_counter.h>
48 #include <lib/parameters/param.h>
49 #include <drivers/drv_hrt.h>
52 
53 /* Configuration Constants */
54 
55 #if defined PX4_SPI_BUS_EXPANSION // crazyflie
56 # define PMW3901_BUS PX4_SPI_BUS_EXPANSION
57 #elif defined PX4_SPI_BUS_EXTERNAL1 // fmu-v5
58 # define PMW3901_BUS PX4_SPI_BUS_EXTERNAL1
59 #elif defined PX4_SPI_BUS_EXTERNAL // fmu-v4 extspi
60 # define PMW3901_BUS PX4_SPI_BUS_EXTERNAL
61 #else
62 # error "add the required spi bus from board_config.h here"
63 #endif
64 
65 #if defined PX4_SPIDEV_EXPANSION_2 // crazyflie flow deck
66 # define PMW3901_SPIDEV PX4_SPIDEV_EXPANSION_2
67 #elif defined PX4_SPIDEV_EXTERNAL1_1 // fmu-v5 ext CS1
68 # define PMW3901_SPIDEV PX4_SPIDEV_EXTERNAL1_1
69 #elif defined PX4_SPIDEV_EXTERNAL // fmu-v4 extspi
70 # define PMW3901_SPIDEV PX4_SPIDEV_EXTERNAL
71 #else
72 # error "add the required spi dev from board_config.h here"
73 #endif
74 
75 #define PMW3901_SPI_BUS_SPEED (2000000L) // 2MHz
76 
77 #define DIR_WRITE(a) ((a) | (1 << 7))
78 #define DIR_READ(a) ((a) & 0x7f)
79 
80 #define PMW3901_DEVICE_PATH "/dev/pmw3901"
81 
82 /* PMW3901 Registers addresses */
83 #define PMW3901_US 1000 /* 1 ms */
84 #define PMW3901_SAMPLE_INTERVAL 10000 /* 10 ms */
85 
86 
87 class PMW3901 : public device::SPI, public px4::ScheduledWorkItem
88 {
89 public:
90  PMW3901(int bus = PMW3901_BUS, enum Rotation yaw_rotation = (enum Rotation)0);
91 
92  virtual ~PMW3901();
93 
94  virtual int init();
95 
96  /**
97  * Diagnostics - print some basic information about the driver.
98  */
99  void print_info();
100 
101 protected:
102  virtual int probe();
103 
104 private:
105 
106  const uint64_t _collect_time{15000}; // usecs, ensures flow data is published every second iteration of Run() (100Hz -> 50Hz)
107 
109 
112 
114 
116 
117  int _flow_sum_x{0};
118  int _flow_sum_y{0};
119  uint64_t _flow_dt_sum_usec{0};
120  uint16_t _flow_quality_sum{0};
122 
123  /**
124  * Initialise the automatic measurement state machine and start it.
125  *
126  * @note This function is called at open and error time. It might make sense
127  * to make it more aggressive about resetting the bus in case of errors.
128  */
129  void start();
130 
131  /**
132  * Stop the automatic measurement state machine.
133  */
134  void stop();
135 
136  /**
137  * Perform a poll cycle; collect from the previous measurement
138  * and start a new one.
139  */
140  void Run() override;
141 
142  int readRegister(unsigned reg, uint8_t *data, unsigned count);
143  int writeRegister(unsigned reg, uint8_t data);
144 
145  int sensorInit();
146  int readMotionCount(int16_t &deltaX, int16_t &deltaY, uint8_t &qual);
147 };
virtual int probe()
Definition: PMW3901.cpp:241
int readRegister(unsigned reg, uint8_t *data, unsigned count)
Definition: PMW3901.cpp:257
uint8_t _flow_sample_counter
Definition: PMW3901.hpp:121
int readMotionCount(int16_t &deltaX, int16_t &deltaY, uint8_t &qual)
Definition: PMW3901.cpp:372
uint64_t _previous_collect_timestamp
Definition: PMW3901.hpp:113
void print_info()
Diagnostics - print some basic information about the driver.
Definition: PMW3901.cpp:417
uORB::PublicationMulti< optical_flow_s > _optical_flow_pub
Definition: PMW3901.hpp:108
Vector rotation library.
High-resolution timer with callouts and timekeeping.
perf_counter_t _comms_errors
Definition: PMW3901.hpp:111
Global flash based parameter store.
int _flow_sum_x
Definition: PMW3901.hpp:117
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
uint64_t _flow_dt_sum_usec
Definition: PMW3901.hpp:119
Header common to all counters.
int sensorInit()
Definition: PMW3901.cpp:58
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition: PMW3901.cpp:299
int _flow_sum_y
Definition: PMW3901.hpp:118
int writeRegister(unsigned reg, uint8_t data)
Definition: PMW3901.cpp:277
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
virtual ~PMW3901()
Definition: PMW3901.cpp:47
void stop()
Stop the automatic measurement state machine.
Definition: PMW3901.cpp:411
enum Rotation _yaw_rotation
Definition: PMW3901.hpp:115
void start()
Initialise the automatic measurement state machine and start it.
Definition: PMW3901.cpp:404
const uint64_t _collect_time
Definition: PMW3901.hpp:106
PMW3901(int bus=PMW3901_BUS, enum Rotation yaw_rotation=(enum Rotation) 0)
Definition: PMW3901.cpp:38
uint16_t _flow_quality_sum
Definition: PMW3901.hpp:120
perf_counter_t _sample_perf
Definition: PMW3901.hpp:110
virtual int init()
Definition: PMW3901.cpp:211
Performance measuring tools.