Firmware
|
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_getopt.h>
#include <px4_workqueue.h>
#include <drivers/device/spi.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <float.h>
#include <conversion/rotation.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/device/integrator.h>
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/sensor_gyro.h>
#include <board_config.h>
Classes | |
class | PMW3901 |
Namespaces | |
pmw3901 | |
Local functions in support of the shell command. | |
Functions | |
__EXPORT int | pmw3901_main (int argc, char *argv[]) |
void | pmw3901::start (int spi_bus) |
Start the driver. | |
void | pmw3901::stop () |
Stop the driver. More... | |
void | pmw3901::test () |
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in polled and automatic modes. | |
void | pmw3901::reset () |
Reset the driver. More... | |
void | pmw3901::info () |
Print a little info about the driver. More... | |
void | pmw3901::usage () |
Print a little info about how to start/stop/use the driver. More... | |
Variables | |
PMW3901 * | pmw3901::g_dev |
Driver for the pmw3901 optical flow sensor connected via SPI.