http://pixhawk.org/modules/px4flow
PX4FLOW Smart Camera
PX4Flow is an optical flow smart camera (it provides the image for setup purposes, but it not designed to capture images like a webcam). It has a native resolution of 752×480 pixels and calculates optical flow on a 4x binned and cropped area at 400 Hz, giving it a very high light sensitivity. Unlike many mouse sensors, it also works indoors and in low outdoor light conditions without the need for an illumination LED. It can be freely reprogrammed to do any other basic, efficient low-level computer vision task.
-
168 MHz Cortex M4F CPU (128 + 64 KB RAM)
-
752×480 MT9V034 image sensor, L3GD20 3D Gyro
-
16 mm M12 lens (IR block filter)
-
Size 45.5 mm x 35mm
-
Power consumption 115mA / 5V
Where to Buy
Order this module from:
-
Unmanned Tech (UK)
-
UAV store (Germany & EU)]]
If out of stock the software-compatible, but not connector-compatible version can be used:
Setup Guides
For PX4IOAR users, here is a setup guide.
Specifications
-
MT9V034 machine vision CMOS sensor with global shutter
-
Optical flow processing at 4×4 binned image at 400 Hz
-
Superior light sensitivity with 24×24 μm super-pixels
-
Onboard 16bit gyroscope up to 2000°/s and 780 Hz update rate, default high precision-mode at 500°/s
-
Onboard sonar input and mount for Maxbotix sonar sensors. (HRLV-EZ4 recommended, SparkFun Product Link)
-
USB bootloader
-
USB serial up to 921600 baud (including live camera view with QGroundControl)
-
USB power option
-
Does fit the MatrixVision Bluefox MV mounting holes (camera center off-centered)
Image Quality and Output
PX4FLOW is not designed as a camera, but does all processing on-chip. The image output is only intended for focusing the lens.
-
Download a version (2.0.1 or later) from QGroundControl: http://qgroundcontrol.org/downloads
-
Unplug your flow sensor
-
In QGroundControl, click on Configuration → Firmware Update. Hit the big green “Scan” button.
-
Connect the flow sensor. Click on upgrade once its detected (leave the default to “stable”)
-
Maximize the QGroundControl window. Click on Tool Widgets → Video Downlink
-
Enjoy the live view and focus the camera by loosening the locking screw and turning the lens at an object at 3m distance.
-
If you want to get higher res to focus the sensor, go to Config → Advanced Config and set the “VIDEO_ONLY” parameter to 1.
Pixhawk Setup
Note: Applies to all PX4 FMU versions, including all versions of Pixhawk.
-
Update the firmware on PX4Flow using QGroundControl (in the top left menu, click on CONFIG, then on Firmware Upgrade)
-
Connect PX4Flow I2C to the Pixhawk I2C
The module will be detected on boot, flow data should be coming through at 10Hz if the autopilot is connected via USB. Flow data is transmitted via wireless at a lower rate.
Orientation
The default orientation (meaning: zero rotation) is defined as Y on flow board pointing towards front of vehicle as shown in the following picture.
The orientation of PX4Flow can be set at PX4 flight stack firmware's parameter.
The detail parameter is listed below and more can be found here.
SENS_FLOW_ROT | PX4Flow board rotation | 0 | ||
This parameter defines the rotation of the PX4FLOW board relative to the platform. Zero rotation is defined as Y on flow board pointing towards front of vehicle Possible values are: 0 = No rotation 1 = Yaw 45° 2 = Yaw 90° 3 = Yaw 135° 4 = Yaw 180° 5 = Yaw 225° 6 = Yaw 270° 7 = Yaw 315° |
Wiring
It is highly recommended to use twisted / shielded I2C wires to minimize radiated noise (I2C spec). From thespec:
If the bus lines are twisted-pairs, each bus line must be twisted with a VSS return. Alternatively, the SCL line can be twisted with a VSS return, and the SDA line twisted with a VDD return. In the latter case, capacitors must be used to decouple the VDD line to the VSS line at both ends of the twisted pairs. If the bus lines are shielded (shield connected to VSS), interference is minimized. However, the shielded cable must have low capacitive coupling between the SDA and SCL lines to minimize crosstalk.
Data Output
The PX4FLOW module outputs MAVLink packets on USB and serial port. Use QGroundControl to read data from the module. An I2C interface for sensor data reading is offered as well. Third party libraries are available to connect and integrate PX4FLOW data in your projects.
-
USART3: MAVLink at 115200, 8N1 baud: OPTICAL_FLOW message, OPTICAL_FLOW_RAD message, HEARTBEAT message
-
USB: Baud rate is not relevant (USB ignores it): OPTICAL_FLOW message, OPTICAL_FLOW_RAD message, HEARTBEAT message, image.
-
I2C1: latest Flow value (i2c_frame) and accumulated Flow (i2c_integral_frame) values since last I2C readout available for readout.
I2C
The 7 Bit I2C Address of the Flow Module is user selectable. Using the solder jumpers on the back of the flow board you can add an offset to the baseaddress 0x42. The address range for the 8 possible choices is: 0x42 - 0x49.
Bit 2 | Bit 1 | Bit 0 | |
---|---|---|---|
7 Bit Address 0x42 (default) | 0 | 0 | 0 |
7 Bit Address 0x43 | 0 | 0 | 1 |
: | : | : | : |
7 Bit Address 0x49 | 1 | 1 | 1 |
For details check the description of the I2C frame and the I2C integral frame
The I2C frame contains 22 bytes of data in the following order:
Register Address | Register Content |
---|---|
0x00 (0) | Framecounter lower byte |
0x01 (1) | Framecounter upper byte |
0x02 (2) | latest Flow*10 in x direction lower byte |
0x03 (3) | latest Flow*10 in x direction upper byte |
: | : |
0x13 (19) | Sonar Timestamp |
0x14 (20) | Grounddistance lower byte |
0x15 (21) | Grounddistance upper byte |
22 Byte Data Packet (send 0x0 to PX4FLOW module and receive back 22 Bytes data, internal address auto increments)
typedef struct i2c_frame { uint16_t frame_count;// counts created I2C frames [#frames] int16_t pixel_flow_x_sum;// latest x flow measurement in pixels*10 [pixels] int16_t pixel_flow_y_sum;// latest y flow measurement in pixels*10 [pixels] int16_t flow_comp_m_x;// x velocity*1000 [meters/sec] int16_t flow_comp_m_y;// y velocity*1000 [meters/sec] int16_t qual;// Optical flow quality / confidence [0: bad, 255: maximum quality] int16_t gyro_x_rate; // latest gyro x rate [rad/sec] int16_t gyro_y_rate; // latest gyro y rate [rad/sec] int16_t gyro_z_rate; // latest gyro z rate [rad/sec] uint8_t gyro_range; // gyro range [0 .. 7] equals [50 deg/sec .. 2000 deg/sec] uint8_t sonar_timestamp;// time since last sonar update [milliseconds] int16_t ground_distance;// Ground distance in meters*1000 [meters]. Positive value: distance known. Negative value: Unknown distance } i2c_frame;
The I2C integral frame contains 25 bytes of data in the following order:
Register Address | Register Content |
---|---|
0x16 (22) | Framecounter since last I2C readout lower byte |
0x17 (23) | Framecounter since last I2C readout upper byte |
0x18 (24) | Accumulated flow in radians*10000 around x axis since last I2C readout lower byte |
0x19 (25) | Accumulated flow in radians*10000 around x axis since last I2C readout upper byte |
: | : |
0x22 (34) | Accumulation timespan in microseconds since last I2C readout byte 0 |
0x23 (35) | Accumulation timespan in microseconds since last I2C readout byte 1 |
0x24 (36) | Accumulation timespan in microseconds since last I2C readout byte 2 |
0x25 (37) | Accumulation timespan in microseconds since last I2C readout byte 3 |
: | : |
0x2A (42) | Grounddistance in meters*1000 lower byte |
0x2B (43) | Grounddistance in meters*1000 upper byte |
0x2C (44) | Temperature in Degree Celsius*100 lower byte |
0x2D (45) | Temperature in Degree Celsius*100 upper byte |
0x2E (46) | Averaged quality of accumulated flow values |
25 Byte Data Packet (send 0x16 (22) to PX4FLOW module and receive back 25 Bytes data, internal address auto increments)
typedef struct i2c_integral_frame { uint16_t frame_count_since_last_readout;//number of flow measurements since last I2C readout [#frames] int16_t pixel_flow_x_integral;//accumulated flow in radians*10000 around x axis since last I2C readout [rad*10000] int16_t pixel_flow_y_integral;//accumulated flow in radians*10000 around y axis since last I2C readout [rad*10000] int16_t gyro_x_rate_integral;//accumulated gyro x rates in radians*10000 since last I2C readout [rad*10000] int16_t gyro_y_rate_integral;//accumulated gyro y rates in radians*10000 since last I2C readout [rad*10000] int16_t gyro_z_rate_integral;//accumulated gyro z rates in radians*10000 since last I2C readout [rad*10000] uint32_t integration_timespan;//accumulation timespan in microseconds since last I2C readout [microseconds] uint32_t sonar_timestamp;// time since last sonar update [microseconds] int16_t ground_distance;// Ground distance in meters*1000 [meters*1000] int16_t gyro_temperature;// Temperature * 100 in centi-degrees Celsius [degcelsius*100] uint8_t quality;// averaged quality of accumulated flow values [0:bad quality;255: max quality] } __attribute__((packed)) i2c_integral_frame;
Accuracy
The ortho photo below shows that a flight on the park roads is accurately measured. This was done with a PX4FMU on a 7“ quad flying at about 1.6 m altitude in manual flight. No GPS, only PX4FLOW integration of position.
Downloads
Manual and Schematics
USB Driver
-
Windows: PX4FMU and PX4FLOW Windows driver: ZIP file, please follow this guide: PX4FLOW Windows Driver Installation
-
Mac OS: Comes with in-built drivers, no additional driver needed
-
Linux: Comes with in-built drivers, no additional driver needed
Papers
The flow module as been accepted as paper to the International Conference on Robotics and Automation (ICRA 2013) in Karlsruhe, Germany.
Dominik Honegger, Lorenz Meier, Petri Tanskanen and Marc Pollefeys. An Open Source and Open Hardware Embedded Metric Optical Flow CMOS Camera for Indoor and Outdoor Applications, ICRA2013 (Full version)
Libraries
The following are third party libraries that can be used to integrate the flow module in your projects .
-
mavros: A general MAVLink ROS interface, maintained by Vladimir Ermakov
-
px-ros-pkg: A PX4FLOW ROS (Robot Operating System) interface, maintained by Lionel Heng ( hengli@inf.ethz.ch).
-
arduino-px4flow-i2c: An Arduino library wrapping the I2C interface, maintained by Laurent Eschenauer ( laurent@eschenauer.be).
Connectors
-
USART2 (J2): Hirose DF13 6 pos ( Digi-Key Link: DF13A-6P-1.25H(20))
-
Mates: Hirose DF13 6 pos housing ( Digi-Key Link: Hirose DF13-6S-1.25C)
-
-
USART3 (J1): Hirose DF13 6 pos ( Digi-Key Link: DF13A-6P-1.25H(20))
-
Mates: Hirose DF13 6 pos housing ( Digi-Key Link: Hirose DF13-6S-1.25C)
-
-
I2C1 (J3): Hirose DF13 4 pos ( Digi-Key Link: DF13A-4P-1.25H(20))
-
Mates: Hirose DF13 4 pos housing ( Digi-Key Link: Hirose DF13-4S-1.25C)
-
-
USB (J5): Micro USB-B
-
Mates: Cell phone data / charger cables, e.g. Digi-Key Link: ASSMANN AK67421-0.5-R
-
-
ARM MINI JTAG (J6, not populated per default ): 1.27 mm 10pos header (SHROUDED, for Black Magic Probe: Samtec FTSH-105-01-F-DV-K or (untested) or Harwin M50-3600542 ( Digikey or Mouser)
-
JTAG Adapter Option #1: BlackMagic Probe, comes without cables, needs the Samtec FFSD-05-D-06.00-01-N cable ( Samtec sample service or Digi-Key Link: SAM8218-ND) and a Mini-USB cable
-
JTAG Adapter Option #2: Digi-Key Link: ST-LINK/V2 / ST USER MANUAL, needs an ARM Mini JTAG to 20pos adapter: Digi-Key Link: 726-1193-ND
-
JTAG Adapter Option #3: SparkFun Link: Olimex ARM-TINY or any other OpenOCD-compatible ARM Cortex JTAG adapter, needs an ARM Mini JTAG to 20pos adapter: Digi-Key Link: 726-1193-ND
-
Optics
The correct optics are delivered by 3D Robotics already mounted and focused.
-
16 mm M12 (S-mount) lens (with IR-cut filter)
The focal length influences the maximum measurable velocity.
maximum velocity = +/- 4 pixels / (1second/internalupdaterate)*grounddistance/focal length in pixels
the internal update rate is 400 Hz
pixelsize is 24 micro meters, a 16mm lens has therefore a focal length of 0.016 meter / 24 micro meter per pixel = 666.666 pixels
Max velocities for different focal length lenses and ground distances:
Grounddistance | 1m | 3m | 10m |
---|---|---|---|
16mm lens | 2.4m/s | 7.2m/s | 24m/s |
8mm lens | 4.8m/s | 14.4m/s | 48m/s |
6mm lens | 6.4m/s | 19.2m/s | 64m/s |
4mm lens | 9.6m/s | 28.8m/s | 96m/s |
max_vel = 4/(1/400)*grounddistance/(focallength/0.000024)