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> 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 62 # error "add the required spi bus from board_config.h here" 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 72 # error "add the required spi dev from board_config.h here" 75 #define PMW3901_SPI_BUS_SPEED (2000000L) // 2MHz 77 #define DIR_WRITE(a) ((a) | (1 << 7)) 78 #define DIR_READ(a) ((a) & 0x7f) 80 #define PMW3901_DEVICE_PATH "/dev/pmw3901" 83 #define PMW3901_US 1000 84 #define PMW3901_SAMPLE_INTERVAL 10000 87 class PMW3901 :
public device::SPI,
public px4::ScheduledWorkItem
int readRegister(unsigned reg, uint8_t *data, unsigned count)
uint8_t _flow_sample_counter
int readMotionCount(int16_t &deltaX, int16_t &deltaY, uint8_t &qual)
uint64_t _previous_collect_timestamp
void print_info()
Diagnostics - print some basic information about the driver.
uORB::PublicationMulti< optical_flow_s > _optical_flow_pub
High-resolution timer with callouts and timekeeping.
perf_counter_t _comms_errors
Global flash based parameter store.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
uint64_t _flow_dt_sum_usec
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
int writeRegister(unsigned reg, uint8_t data)
Rotation
Enum for board and external compass rotations.
void stop()
Stop the automatic measurement state machine.
enum Rotation _yaw_rotation
void start()
Initialise the automatic measurement state machine and start it.
const uint64_t _collect_time
PMW3901(int bus=PMW3901_BUS, enum Rotation yaw_rotation=(enum Rotation) 0)
uint16_t _flow_quality_sum
perf_counter_t _sample_perf
Performance measuring tools.