|
|
|
@ -62,6 +62,8 @@
@@ -62,6 +62,8 @@
|
|
|
|
|
#include <systemlib/perf_counter.h> |
|
|
|
|
#include <systemlib/err.h> |
|
|
|
|
|
|
|
|
|
#include <conversion/rotation.h> |
|
|
|
|
|
|
|
|
|
#include <drivers/drv_hrt.h> |
|
|
|
|
#include <drivers/drv_px4flow.h> |
|
|
|
|
#include <drivers/device/ringbuffer.h> |
|
|
|
@ -126,7 +128,7 @@ struct i2c_integral_frame f_integral;
@@ -126,7 +128,7 @@ struct i2c_integral_frame f_integral;
|
|
|
|
|
class PX4FLOW: public device::I2C |
|
|
|
|
{ |
|
|
|
|
public: |
|
|
|
|
PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS); |
|
|
|
|
PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS, enum Rotation rotation = (enum Rotation)0); |
|
|
|
|
virtual ~PX4FLOW(); |
|
|
|
|
|
|
|
|
|
virtual int init(); |
|
|
|
@ -155,6 +157,8 @@ private:
@@ -155,6 +157,8 @@ private:
|
|
|
|
|
perf_counter_t _sample_perf; |
|
|
|
|
perf_counter_t _comms_errors; |
|
|
|
|
perf_counter_t _buffer_overflows; |
|
|
|
|
|
|
|
|
|
enum Rotation _sensor_rotation; |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Test whether the device supported by the driver is present at a |
|
|
|
@ -200,7 +204,7 @@ private:
@@ -200,7 +204,7 @@ private:
|
|
|
|
|
*/ |
|
|
|
|
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]); |
|
|
|
|
|
|
|
|
|
PX4FLOW::PX4FLOW(int bus, int address) : |
|
|
|
|
PX4FLOW::PX4FLOW(int bus, int address, enum Rotation rotation) : |
|
|
|
|
I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, PX4FLOW_I2C_MAX_BUS_SPEED), /* 100-400 KHz */ |
|
|
|
|
_reports(nullptr), |
|
|
|
|
_sensor_ok(false), |
|
|
|
@ -209,7 +213,8 @@ PX4FLOW::PX4FLOW(int bus, int address) :
@@ -209,7 +213,8 @@ PX4FLOW::PX4FLOW(int bus, int address) :
|
|
|
|
|
_px4flow_topic(-1), |
|
|
|
|
_sample_perf(perf_alloc(PC_ELAPSED, "px4flow_read")), |
|
|
|
|
_comms_errors(perf_alloc(PC_COUNT, "px4flow_comms_errors")), |
|
|
|
|
_buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows")) |
|
|
|
|
_buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows")), |
|
|
|
|
_sensor_rotation(rotation) |
|
|
|
|
{ |
|
|
|
|
// enable debug() calls
|
|
|
|
|
_debug_enabled = false; |
|
|
|
@ -362,6 +367,13 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
@@ -362,6 +367,13 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|
|
|
|
case SENSORIOCGQUEUEDEPTH: |
|
|
|
|
return _reports->size(); |
|
|
|
|
|
|
|
|
|
case SENSORIOCSROTATION: |
|
|
|
|
_sensor_rotation = (enum Rotation)arg; |
|
|
|
|
return OK; |
|
|
|
|
|
|
|
|
|
case SENSORIOCGROTATION: |
|
|
|
|
return _sensor_rotation; |
|
|
|
|
|
|
|
|
|
case SENSORIOCRESET: |
|
|
|
|
/* XXX implement this */ |
|
|
|
|
return -EINVAL; |
|
|
|
@ -536,6 +548,10 @@ PX4FLOW::collect()
@@ -536,6 +548,10 @@ PX4FLOW::collect()
|
|
|
|
|
report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
|
|
|
|
|
|
|
|
|
|
report.sensor_id = 0; |
|
|
|
|
|
|
|
|
|
/* rotate measurements according to parameter */ |
|
|
|
|
float zeroval = 0.0f; |
|
|
|
|
rotate_3f(_sensor_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval);
|
|
|
|
|
|
|
|
|
|
if (_px4flow_topic < 0) { |
|
|
|
|
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report); |
|
|
|
|