PX4 Firmware
PX4 Autopilot Software http://px4.io
PMW3901 Class Reference

#include <PMW3901.hpp>

Inheritance diagram for PMW3901:
Collaboration diagram for PMW3901:

Public Member Functions

 PMW3901 (int bus=PMW3901_BUS, enum Rotation yaw_rotation=(enum Rotation) 0)
 
virtual ~PMW3901 ()
 
virtual int init ()
 
void print_info ()
 Diagnostics - print some basic information about the driver. More...
 

Protected Member Functions

virtual int probe ()
 

Private Member Functions

void start ()
 Initialise the automatic measurement state machine and start it. More...
 
void stop ()
 Stop the automatic measurement state machine. More...
 
void Run () override
 Perform a poll cycle; collect from the previous measurement and start a new one. More...
 
int readRegister (unsigned reg, uint8_t *data, unsigned count)
 
int writeRegister (unsigned reg, uint8_t data)
 
int sensorInit ()
 
int readMotionCount (int16_t &deltaX, int16_t &deltaY, uint8_t &qual)
 

Private Attributes

const uint64_t _collect_time {15000}
 
uORB::PublicationMulti< optical_flow_s_optical_flow_pub {ORB_ID(optical_flow)}
 
perf_counter_t _sample_perf
 
perf_counter_t _comms_errors
 
uint64_t _previous_collect_timestamp {0}
 
enum Rotation _yaw_rotation
 
int _flow_sum_x {0}
 
int _flow_sum_y {0}
 
uint64_t _flow_dt_sum_usec {0}
 
uint16_t _flow_quality_sum {0}
 
uint8_t _flow_sample_counter {0}
 

Detailed Description

Definition at line 87 of file PMW3901.hpp.

Constructor & Destructor Documentation

◆ PMW3901()

PMW3901::PMW3901 ( int  bus = PMW3901_BUS,
enum Rotation  yaw_rotation = (enum Rotation)0 
)

Definition at line 38 of file PMW3901.cpp.

◆ ~PMW3901()

PMW3901::~PMW3901 ( )
virtual

Definition at line 47 of file PMW3901.cpp.

References _comms_errors, _sample_perf, perf_free(), and stop().

Here is the call graph for this function:

Member Function Documentation

◆ init()

int PMW3901::init ( )
virtual

Definition at line 211 of file PMW3901.cpp.

References _previous_collect_timestamp, _yaw_rotation, hrt_absolute_time(), ToneAlarmInterface::init(), OK, param_find(), param_get(), PARAM_INVALID, sensorInit(), and start().

Referenced by pmw3901::start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_info()

void PMW3901::print_info ( )

Diagnostics - print some basic information about the driver.

Definition at line 417 of file PMW3901.cpp.

References _comms_errors, _sample_perf, and perf_print_counter().

Referenced by pmw3901::info().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ probe()

int PMW3901::probe ( )
protectedvirtual

Definition at line 241 of file PMW3901.cpp.

References data, OK, and readRegister().

Here is the call graph for this function:

◆ readMotionCount()

int PMW3901::readMotionCount ( int16_t &  deltaX,
int16_t &  deltaY,
uint8_t &  qual 
)
private

Definition at line 372 of file PMW3901.cpp.

References _comms_errors, data, DEVICE_LOG, DIR_READ, OK, and perf_count().

Referenced by Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ readRegister()

int PMW3901::readRegister ( unsigned  reg,
uint8_t *  data,
unsigned  count 
)
private

Definition at line 257 of file PMW3901.cpp.

References _comms_errors, DEVICE_LOG, DIR_READ, OK, and perf_count().

Referenced by probe(), and sensorInit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

void PMW3901::Run ( )
overrideprivate

Perform a poll cycle; collect from the previous measurement and start a new one.

Definition at line 299 of file PMW3901.cpp.

References _collect_time, _flow_dt_sum_usec, _flow_quality_sum, _flow_sample_counter, _flow_sum_x, _flow_sum_y, _optical_flow_pub, _previous_collect_timestamp, _sample_perf, _yaw_rotation, f(), hrt_absolute_time(), perf_begin(), perf_end(), uORB::PublicationMulti< T >::publish(), readMotionCount(), rotate_3f(), and optical_flow_s::timestamp.

Here is the call graph for this function:

◆ sensorInit()

int PMW3901::sensorInit ( )
private

Definition at line 58 of file PMW3901.cpp.

References data, readRegister(), and writeRegister().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void PMW3901::start ( )
private

Initialise the automatic measurement state machine and start it.

Note
This function is called at open and error time. It might make sense to make it more aggressive about resetting the bus in case of errors.

Definition at line 404 of file PMW3901.cpp.

References PMW3901_SAMPLE_INTERVAL, and PMW3901_US.

Referenced by init().

Here is the caller graph for this function:

◆ stop()

void PMW3901::stop ( )
private

Stop the automatic measurement state machine.

Definition at line 411 of file PMW3901.cpp.

Referenced by ~PMW3901().

Here is the caller graph for this function:

◆ writeRegister()

int PMW3901::writeRegister ( unsigned  reg,
uint8_t  data 
)
private

Definition at line 277 of file PMW3901.cpp.

References _comms_errors, data, DEVICE_LOG, DIR_WRITE, OK, perf_count(), and TIME_us_TSWW.

Referenced by sensorInit().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _collect_time

const uint64_t PMW3901::_collect_time {15000}
private

Definition at line 106 of file PMW3901.hpp.

Referenced by Run().

◆ _comms_errors

perf_counter_t PMW3901::_comms_errors
private

Definition at line 111 of file PMW3901.hpp.

Referenced by print_info(), readMotionCount(), readRegister(), writeRegister(), and ~PMW3901().

◆ _flow_dt_sum_usec

uint64_t PMW3901::_flow_dt_sum_usec {0}
private

Definition at line 119 of file PMW3901.hpp.

Referenced by Run().

◆ _flow_quality_sum

uint16_t PMW3901::_flow_quality_sum {0}
private

Definition at line 120 of file PMW3901.hpp.

Referenced by Run().

◆ _flow_sample_counter

uint8_t PMW3901::_flow_sample_counter {0}
private

Definition at line 121 of file PMW3901.hpp.

Referenced by Run().

◆ _flow_sum_x

int PMW3901::_flow_sum_x {0}
private

Definition at line 117 of file PMW3901.hpp.

Referenced by Run().

◆ _flow_sum_y

int PMW3901::_flow_sum_y {0}
private

Definition at line 118 of file PMW3901.hpp.

Referenced by Run().

◆ _optical_flow_pub

uORB::PublicationMulti<optical_flow_s> PMW3901::_optical_flow_pub {ORB_ID(optical_flow)}
private

Definition at line 108 of file PMW3901.hpp.

Referenced by Run().

◆ _previous_collect_timestamp

uint64_t PMW3901::_previous_collect_timestamp {0}
private

Definition at line 113 of file PMW3901.hpp.

Referenced by init(), and Run().

◆ _sample_perf

perf_counter_t PMW3901::_sample_perf
private

Definition at line 110 of file PMW3901.hpp.

Referenced by print_info(), Run(), and ~PMW3901().

◆ _yaw_rotation

enum Rotation PMW3901::_yaw_rotation
private

Definition at line 115 of file PMW3901.hpp.

Referenced by init(), and Run().


The documentation for this class was generated from the following files: