aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-12-26 17:06:19 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-12-26 17:06:19 +0100
commit407889ea2c472ed5be950307bb5dc27f07f88006 (patch)
tree0dacd8384fd8a136c27163da1e22a086a0b9d3d5 /src/drivers
parentf3a224e30d8a70418541a6185ce5765b37745a7a (diff)
parent5c51adf5f79266de2b483c2461babd4d673cfffb (diff)
downloadpx4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.tar.gz
px4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.tar.bz2
px4-firmware-407889ea2c472ed5be950307bb5dc27f07f88006.zip
Merged master into indoor branch
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/airspeed/airspeed.cpp10
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/boards/aerocore/aerocore_led.c3
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c2
-rw-r--r--src/drivers/gps/gps.cpp1
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp39
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp2
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp22
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp2
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp44
-rw-r--r--src/drivers/px4flow/module.mk2
-rw-r--r--src/drivers/px4flow/px4flow.cpp345
-rw-r--r--src/drivers/px4io/px4io.cpp91
-rw-r--r--src/drivers/rgbled/rgbled.cpp14
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp2
-rw-r--r--src/drivers/sf0x/sf0x.cpp4
-rw-r--r--src/drivers/stm32/drv_hrt.c8
-rw-r--r--src/drivers/trone/module.mk44
-rw-r--r--src/drivers/trone/trone.cpp915
20 files changed, 1324 insertions, 230 deletions
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 3a1e1b7b5..6db6713c4 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -159,13 +159,15 @@ out:
int
Airspeed::probe()
{
- /* on initial power up the device needs more than one retry
- for detection. Once it is running then retries aren't
- needed
+ /* on initial power up the device may need more than one retry
+ for detection. Once it is running the number of retries can
+ be reduced
*/
_retries = 4;
int ret = measure();
- _retries = 0;
+
+ // drop back to 2 retries once initialised
+ _retries = 2;
return ret;
}
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 9d2c1441d..7f1b21a95 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 15,
1100,
ardrone_interface_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/boards/aerocore/aerocore_led.c b/src/drivers/boards/aerocore/aerocore_led.c
index e40d1730c..94a716029 100644
--- a/src/drivers/boards/aerocore/aerocore_led.c
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -45,6 +45,7 @@
#include "board_config.h"
#include <arch/board/board.h>
+#include <systemlib/err.h>
/*
* Ideally we'd be able to get these from up_internal.h,
@@ -54,7 +55,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index bccdf1190..5035600ef 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -221,7 +221,7 @@ int frsky_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
frsky_telemetry_thread_main,
- (const char **)argv);
+ (char * const *)argv);
while (!thread_running) {
usleep(200);
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 5fb4b9ff8..47c907bd3 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -274,7 +274,6 @@ GPS::task_main_trampoline(void *arg)
void
GPS::task_main()
{
- log("starting");
/* open the serial port */
_serial_fd = ::open(_port, O_RDWR);
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 81f767965..d4dbf3778 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1349,7 +1349,7 @@ HMC5883 *g_dev_ext = nullptr;
void start(int bus, enum Rotation rotation);
void test(int bus);
void reset(int bus);
-void info(int bus);
+int info(int bus);
int calibrate(int bus);
void usage();
@@ -1595,17 +1595,23 @@ reset(int bus)
/**
* Print a little info about the driver.
*/
-void
+int
info(int bus)
{
- HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
- if (g_dev == nullptr)
- errx(1, "driver not running");
+ int ret = 1;
+
+ HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD ? g_dev_int : g_dev_ext);
+ if (g_dev == nullptr) {
+ warnx("not running on bus %d", bus);
+ } else {
- printf("state @ %p\n", g_dev);
- g_dev->print_info();
+ warnx("running on bus: %d (%s)\n", bus, ((PX4_I2C_BUS_ONBOARD) ? "onboard" : "offboard"));
- exit(0);
+ g_dev->print_info();
+ ret = 0;
+ }
+
+ return ret;
}
void
@@ -1685,8 +1691,21 @@ hmc5883_main(int argc, char *argv[])
/*
* Print driver information.
*/
- if (!strcmp(verb, "info") || !strcmp(verb, "status"))
- hmc5883::info(bus);
+ if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
+ if (bus == -1) {
+ int ret = 0;
+ if (hmc5883::info(PX4_I2C_BUS_ONBOARD)) {
+ ret = 1;
+ }
+
+ if (hmc5883::info(PX4_I2C_BUS_EXPANSION)) {
+ ret = 1;
+ }
+ exit(ret);
+ } else {
+ exit(hmc5883::info(bus));
+ }
+ }
/*
* Autocalibrate the scaling
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index 8ab9d8d55..4b8e0c0b0 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -214,7 +214,7 @@ hott_sensors_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
1024,
hott_sensors_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index edbb14172..17a24d104 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -240,7 +240,7 @@ hott_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp
index 6793acd81..4676c6ad7 100644
--- a/src/drivers/ll40ls/ll40ls.cpp
+++ b/src/drivers/ll40ls/ll40ls.cpp
@@ -89,7 +89,7 @@
/* Device limits */
#define LL40LS_MIN_DISTANCE (0.00f)
-#define LL40LS_MAX_DISTANCE (14.00f)
+#define LL40LS_MAX_DISTANCE (60.00f)
#define LL40LS_CONVERSION_INTERVAL 100000 /* 100ms */
@@ -233,11 +233,11 @@ LL40LS::~LL40LS()
if (_reports != nullptr) {
delete _reports;
}
-
+
if (_class_instance != -1) {
unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
}
-
+
// free perf counters
perf_free(_sample_perf);
perf_free(_comms_errors);
@@ -263,7 +263,7 @@ LL40LS::init()
_class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
- if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
/* get a publish handle on the range finder topic */
struct range_finder_report rf_report;
measure();
@@ -314,9 +314,9 @@ LL40LS::probe()
goto ok;
}
- debug("WHO_AM_I byte mismatch 0x%02x should be 0x%02x val=0x%02x\n",
- (unsigned)who_am_i,
- LL40LS_WHO_AM_I_REG_VAL,
+ debug("WHO_AM_I byte mismatch 0x%02x should be 0x%02x val=0x%02x\n",
+ (unsigned)who_am_i,
+ LL40LS_WHO_AM_I_REG_VAL,
(unsigned)val);
}
@@ -581,6 +581,8 @@ LL40LS::collect()
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
+ report.minimum_distance = get_minimum_distance();
+ report.maximum_distance = get_maximum_distance();
if (si_units > get_minimum_distance() && si_units < get_maximum_distance()) {
report.valid = 1;
}
@@ -704,7 +706,7 @@ LL40LS::print_info()
perf_print_counter(_buffer_overflows);
printf("poll interval: %u ticks\n", _measure_ticks);
_reports->print_info("report queue");
- printf("distance: %ucm (0x%04x)\n",
+ printf("distance: %ucm (0x%04x)\n",
(unsigned)_last_distance, (unsigned)_last_distance);
}
@@ -969,8 +971,8 @@ ll40ls_main(int argc, char *argv[])
}
}
- const char *verb = argv[optind];
-
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index beb6c8e35..9cf568658 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -520,6 +520,8 @@ MB12XX::collect()
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
+ report.minimum_distance = get_minimum_distance();
+ report.maximum_distance = get_maximum_distance();
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
/* publish it, if we are the primary */
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index a95e041a1..c9c27892f 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -194,6 +194,8 @@ public:
*/
void print_info();
+ void print_registers();
+
protected:
virtual int probe();
@@ -1414,6 +1416,21 @@ MPU6000::print_info()
_gyro_reports->print_info("gyro queue");
}
+void
+MPU6000::print_registers()
+{
+ printf("MPU6000 registers\n");
+ for (uint8_t reg=MPUREG_PRODUCT_ID; reg<=108; reg++) {
+ uint8_t v = read_reg(reg);
+ printf("%02x:%02x ",(unsigned)reg, (unsigned)v);
+ if ((reg - (MPUREG_PRODUCT_ID-1)) % 13 == 0) {
+ printf("\n");
+ }
+ }
+ printf("\n");
+}
+
+
MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) :
CDev("MPU6000_gyro", path),
_parent(parent),
@@ -1479,6 +1496,7 @@ void start(bool, enum Rotation);
void test(bool);
void reset(bool);
void info(bool);
+void regdump(bool);
void usage();
/**
@@ -1654,10 +1672,26 @@ info(bool external_bus)
exit(0);
}
+/**
+ * Dump the register information
+ */
+void
+regdump(bool external_bus)
+{
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
+ errx(1, "driver not running");
+
+ printf("regdump @ %p\n", *g_dev_ptr);
+ (*g_dev_ptr)->print_registers();
+
+ exit(0);
+}
+
void
usage()
{
- warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
@@ -1714,5 +1748,11 @@ mpu6000_main(int argc, char *argv[])
if (!strcmp(verb, "info"))
mpu6000::info(external_bus);
- errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+ /*
+ * Print register information.
+ */
+ if (!strcmp(verb, "regdump"))
+ mpu6000::regdump(external_bus);
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info' or 'regdump'");
}
diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk
index 460bec7b9..ecd3e804a 100644
--- a/src/drivers/px4flow/module.mk
+++ b/src/drivers/px4flow/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-attributes
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index 804027b05..62308fc65 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -73,15 +73,13 @@
#include <board_config.h>
/* Configuration Constants */
-#define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION
#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
//range 0x42 - 0x49
/* PX4FLOW Registers addresses */
-#define PX4FLOW_REG 0x00 /* Measure Register */
-
-#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz */
+#define PX4FLOW_REG 0x16 /* Measure Register 22*/
+#define PX4FLOW_CONVERSION_INTERVAL 20000 //in microseconds! 20000 = 50 Hz 100000 = 10Hz
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
@@ -92,28 +90,42 @@ static const int ERROR = -1;
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
-//struct i2c_frame
-//{
-// uint16_t frame_count;
-// int16_t pixel_flow_x_sum;
-// int16_t pixel_flow_y_sum;
-// int16_t flow_comp_m_x;
-// int16_t flow_comp_m_y;
-// int16_t qual;
-// int16_t gyro_x_rate;
-// int16_t gyro_y_rate;
-// int16_t gyro_z_rate;
-// uint8_t gyro_range;
-// uint8_t sonar_timestamp;
-// int16_t ground_distance;
-//};
-//
-//struct i2c_frame f;
-
-class PX4FLOW : public device::I2C
+struct i2c_frame {
+ uint16_t frame_count;
+ int16_t pixel_flow_x_sum;
+ int16_t pixel_flow_y_sum;
+ int16_t flow_comp_m_x;
+ int16_t flow_comp_m_y;
+ int16_t qual;
+ int16_t gyro_x_rate;
+ int16_t gyro_y_rate;
+ int16_t gyro_z_rate;
+ uint8_t gyro_range;
+ uint8_t sonar_timestamp;
+ int16_t ground_distance;
+};
+struct i2c_frame f;
+
+struct i2c_integral_frame {
+ uint16_t frame_count_since_last_readout;
+ int16_t pixel_flow_x_integral;
+ int16_t pixel_flow_y_integral;
+ int16_t gyro_x_rate_integral;
+ int16_t gyro_y_rate_integral;
+ int16_t gyro_z_rate_integral;
+ uint32_t integration_timespan;
+ uint32_t time_since_last_sonar_update;
+ uint16_t ground_distance;
+ int16_t gyro_temperature;
+ uint8_t qual;
+} __attribute__((packed));
+struct i2c_integral_frame f_integral;
+
+
+class PX4FLOW: public device::I2C
{
public:
- PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
+ PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS);
virtual ~PX4FLOW();
virtual int init();
@@ -122,8 +134,8 @@ public:
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
/**
- * Diagnostics - print some basic information about the driver.
- */
+ * Diagnostics - print some basic information about the driver.
+ */
void print_info();
protected:
@@ -144,42 +156,41 @@ private:
perf_counter_t _buffer_overflows;
/**
- * Test whether the device supported by the driver is present at a
- * specific address.
- *
- * @param address The I2C bus address to probe.
- * @return True if the device is present.
- */
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
int probe_address(uint8_t address);
/**
- * 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.
- */
+ * 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.
+ */
void start();
/**
- * Stop the automatic measurement state machine.
- */
+ * Stop the automatic measurement state machine.
+ */
void stop();
/**
- * Perform a poll cycle; collect from the previous measurement
- * and start a new one.
- */
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
void cycle();
int measure();
int collect();
/**
- * Static trampoline from the workq context; because we don't have a
- * generic workq wrapper yet.
- *
- * @param arg Instance pointer for the driver that is polling.
- */
- static void cycle_trampoline(void *arg);
-
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
};
@@ -189,7 +200,7 @@ private:
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
PX4FLOW::PX4FLOW(int bus, int address) :
- I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000),//400khz
+ I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000), //400khz
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
@@ -228,21 +239,12 @@ PX4FLOW::init()
}
/* allocate basic report buffers */
- _reports = new RingBuffer(2, sizeof(struct optical_flow_s));
+ _reports = new RingBuffer(2, sizeof(optical_flow_s));
if (_reports == nullptr) {
goto out;
}
- /* get a publish handle on the px4flow topic */
- struct optical_flow_s zero_report;
- memset(&zero_report, 0, sizeof(zero_report));
- _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
-
- if (_px4flow_topic < 0) {
- warnx("failed to create px4flow object. Did you start uOrb?");
- }
-
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
_sensor_ok = true;
@@ -410,9 +412,6 @@ PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
break;
}
- /* wait for it to complete */
- usleep(PX4FLOW_CONVERSION_INTERVAL);
-
/* run the collection phase */
if (OK != collect()) {
ret = -EIO;
@@ -442,6 +441,7 @@ PX4FLOW::measure()
if (OK != ret) {
perf_count(_comms_errors);
+ debug("i2c::transfer returned %d", ret);
return ret;
}
@@ -453,14 +453,20 @@ PX4FLOW::measure()
int
PX4FLOW::collect()
{
- int ret = -EIO;
+ int ret = -EIO;
/* read from the sensor */
- uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+ uint8_t val[47] = { 0 };
perf_begin(_sample_perf);
- ret = transfer(nullptr, 0, &val[0], 22);
+ if (PX4FLOW_REG == 0x00) {
+ ret = transfer(nullptr, 0, &val[0], 47); // read 47 bytes (22+25 : frame1 + frame2)
+ }
+
+ if (PX4FLOW_REG == 0x16) {
+ ret = transfer(nullptr, 0, &val[0], 25); // read 25 bytes (only frame2)
+ }
if (ret < 0) {
debug("error reading from sensor: %d", ret);
@@ -469,36 +475,74 @@ PX4FLOW::collect()
return ret;
}
-// f.frame_count = val[1] << 8 | val[0];
-// f.pixel_flow_x_sum= val[3] << 8 | val[2];
-// f.pixel_flow_y_sum= val[5] << 8 | val[4];
-// f.flow_comp_m_x= val[7] << 8 | val[6];
-// f.flow_comp_m_y= val[9] << 8 | val[8];
-// f.qual= val[11] << 8 | val[10];
-// f.gyro_x_rate= val[13] << 8 | val[12];
-// f.gyro_y_rate= val[15] << 8 | val[14];
-// f.gyro_z_rate= val[17] << 8 | val[16];
-// f.gyro_range= val[18];
-// f.sonar_timestamp= val[19];
-// f.ground_distance= val[21] << 8 | val[20];
+ if (PX4FLOW_REG == 0) {
+ f.frame_count = val[1] << 8 | val[0];
+ f.pixel_flow_x_sum = val[3] << 8 | val[2];
+ f.pixel_flow_y_sum = val[5] << 8 | val[4];
+ f.flow_comp_m_x = val[7] << 8 | val[6];
+ f.flow_comp_m_y = val[9] << 8 | val[8];
+ f.qual = val[11] << 8 | val[10];
+ f.gyro_x_rate = val[13] << 8 | val[12];
+ f.gyro_y_rate = val[15] << 8 | val[14];
+ f.gyro_z_rate = val[17] << 8 | val[16];
+ f.gyro_range = val[18];
+ f.sonar_timestamp = val[19];
+ f.ground_distance = val[21] << 8 | val[20];
+
+ f_integral.frame_count_since_last_readout = val[23] << 8 | val[22];
+ f_integral.pixel_flow_x_integral = val[25] << 8 | val[24];
+ f_integral.pixel_flow_y_integral = val[27] << 8 | val[26];
+ f_integral.gyro_x_rate_integral = val[29] << 8 | val[28];
+ f_integral.gyro_y_rate_integral = val[31] << 8 | val[30];
+ f_integral.gyro_z_rate_integral = val[33] << 8 | val[32];
+ f_integral.integration_timespan = val[37] << 24 | val[36] << 16
+ | val[35] << 8 | val[34];
+ f_integral.time_since_last_sonar_update = val[41] << 24 | val[40] << 16
+ | val[39] << 8 | val[38];
+ f_integral.ground_distance = val[43] << 8 | val[42];
+ f_integral.gyro_temperature = val[45] << 8 | val[44];
+ f_integral.qual = val[46];
+ }
+
+ if (PX4FLOW_REG == 0x16) {
+ f_integral.frame_count_since_last_readout = val[1] << 8 | val[0];
+ f_integral.pixel_flow_x_integral = val[3] << 8 | val[2];
+ f_integral.pixel_flow_y_integral = val[5] << 8 | val[4];
+ f_integral.gyro_x_rate_integral = val[7] << 8 | val[6];
+ f_integral.gyro_y_rate_integral = val[9] << 8 | val[8];
+ f_integral.gyro_z_rate_integral = val[11] << 8 | val[10];
+ f_integral.integration_timespan = val[15] << 24 | val[14] << 16 | val[13] << 8 | val[12];
+ f_integral.time_since_last_sonar_update = val[19] << 24 | val[18] << 16 | val[17] << 8 | val[16];
+ f_integral.ground_distance = val[21] << 8 | val[20];
+ f_integral.gyro_temperature = val[23] << 8 | val[22];
+ f_integral.qual = val[24];
+ }
- int16_t flowcx = val[7] << 8 | val[6];
- int16_t flowcy = val[9] << 8 | val[8];
- int16_t gdist = val[21] << 8 | val[20];
struct optical_flow_s report;
- report.flow_comp_x_m = float(flowcx) / 1000.0f;
- report.flow_comp_y_m = float(flowcy) / 1000.0f;
- report.flow_raw_x = val[3] << 8 | val[2];
- report.flow_raw_y = val[5] << 8 | val[4];
- report.ground_distance_m = float(gdist) / 1000.0f;
- report.quality = val[10];
- report.sensor_id = 0;
+
report.timestamp = hrt_absolute_time();
+ report.pixel_flow_x_integral = static_cast<float>(f_integral.pixel_flow_x_integral) / 10000.0f;//convert to radians
+ report.pixel_flow_y_integral = static_cast<float>(f_integral.pixel_flow_y_integral) / 10000.0f;//convert to radians
+ report.frame_count_since_last_readout = f_integral.frame_count_since_last_readout;
+ report.ground_distance_m = static_cast<float>(f_integral.ground_distance) / 1000.0f;//convert to meters
+ report.quality = f_integral.qual; //0:bad ; 255 max quality
+ report.gyro_x_rate_integral = static_cast<float>(f_integral.gyro_x_rate_integral) / 10000.0f; //convert to radians
+ report.gyro_y_rate_integral = static_cast<float>(f_integral.gyro_y_rate_integral) / 10000.0f; //convert to radians
+ report.gyro_z_rate_integral = static_cast<float>(f_integral.gyro_z_rate_integral) / 10000.0f; //convert to radians
+ report.integration_timespan = f_integral.integration_timespan; //microseconds
+ report.time_since_last_sonar_update = f_integral.time_since_last_sonar_update;//microseconds
+ report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
+
+ report.sensor_id = 0;
+ if (_px4flow_topic < 0) {
+ _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report);
- /* publish it */
- orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
+ } else {
+ /* publish it */
+ orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
+ }
/* post a report to the ring */
if (_reports->force(&report)) {
@@ -558,50 +602,21 @@ PX4FLOW::cycle_trampoline(void *arg)
void
PX4FLOW::cycle()
{
- /* collection phase? */
- if (_collect_phase) {
-
- /* perform collection */
- if (OK != collect()) {
- debug("collection error");
- /* restart the measurement state machine */
- start();
- return;
- }
-
- /* next phase is measurement */
- _collect_phase = false;
-
- /*
- * Is there a collect->measure gap?
- */
- if (_measure_ticks > USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
-
- /* schedule a fresh cycle call when we are ready to measure again */
- work_queue(HPWORK,
- &_work,
- (worker_t)&PX4FLOW::cycle_trampoline,
- this,
- _measure_ticks - USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
-
- return;
- }
- }
-
- /* measurement phase */
if (OK != measure()) {
debug("measure error");
}
- /* next phase is collection */
- _collect_phase = true;
+ /* perform collection */
+ if (OK != collect()) {
+ debug("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this,
+ _measure_ticks);
- /* schedule a fresh cycle call when the measurement is done */
- work_queue(HPWORK,
- &_work,
- (worker_t)&PX4FLOW::cycle_trampoline,
- this,
- USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
}
void
@@ -647,14 +662,41 @@ start()
}
/* create the driver */
- g_dev = new PX4FLOW(PX4FLOW_BUS);
+ g_dev = new PX4FLOW(PX4_I2C_BUS_EXPANSION);
if (g_dev == nullptr) {
goto fail;
}
if (OK != g_dev->init()) {
- goto fail;
+
+ #ifdef PX4_I2C_BUS_ESC
+ delete g_dev;
+ /* try 2nd bus */
+ g_dev = new PX4FLOW(PX4_I2C_BUS_ESC);
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ #endif
+
+ delete g_dev;
+ /* try 3rd bus */
+ g_dev = new PX4FLOW(PX4_I2C_BUS_ONBOARD);
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ goto fail;
+ }
+
+ #ifdef PX4_I2C_BUS_ESC
+ }
+ #endif
}
/* set the poll rate to default, starts automatic data collection */
@@ -683,7 +725,8 @@ fail:
/**
* Stop the driver
*/
-void stop()
+void
+stop()
{
if (g_dev != nullptr) {
delete g_dev;
@@ -714,6 +757,7 @@ test()
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
}
+
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -723,18 +767,18 @@ test()
}
warnx("single read");
- warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
- warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
- warnx("time: %lld", report.timestamp);
-
+ warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
+ warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
+ warnx("framecount_integral: %u",
+ f_integral.frame_count_since_last_readout);
- /* start the sensor polling at 2Hz */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
- errx(1, "failed to set 2Hz poll rate");
+ /* start the sensor polling at 10Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 10)) {
+ errx(1, "failed to set 10Hz poll rate");
}
/* read the sensor 5x and report each value */
- for (unsigned i = 0; i < 5; i++) {
+ for (unsigned i = 0; i < 10; i++) {
struct pollfd fds;
/* wait for data to be ready */
@@ -754,9 +798,22 @@ test()
}
warnx("periodic read %u", i);
- warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
- warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
- warnx("time: %lld", report.timestamp);
+
+ warnx("framecount_total: %u", f.frame_count);
+ warnx("framecount_integral: %u",
+ f_integral.frame_count_since_last_readout);
+ warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
+ warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
+ warnx("gyro_x_rate_integral: %i", f_integral.gyro_x_rate_integral);
+ warnx("gyro_y_rate_integral: %i", f_integral.gyro_y_rate_integral);
+ warnx("gyro_z_rate_integral: %i", f_integral.gyro_z_rate_integral);
+ warnx("integration_timespan [us]: %u", f_integral.integration_timespan);
+ warnx("ground_distance: %0.2f m",
+ (double) f_integral.ground_distance / 1000);
+ warnx("time since last sonar update [us]: %i",
+ f_integral.time_since_last_sonar_update);
+ warnx("quality integration average : %i", f_integral.qual);
+ warnx("quality : %i", f.qual);
}
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 519ba663a..58390ba4c 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -817,6 +817,11 @@ PX4IO::init()
}
+ /* set safety to off if circuit breaker enabled */
+ if (circuit_breaker_enabled("CBRK_IO_SAFETY", CBRK_IO_SAFETY_KEY)) {
+ (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
+ }
+
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
@@ -1155,52 +1160,54 @@ PX4IO::io_set_arming_state()
actuator_armed_s armed; ///< system armed state
vehicle_control_mode_s control_mode; ///< vehicle_control_mode
- orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
- orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
+ int have_armed = orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
+ int have_control_mode = orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
uint16_t set = 0;
uint16_t clear = 0;
- if (armed.armed) {
- set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
-
- } else {
- clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
- }
-
- if (armed.lockdown && !_lockdown_override) {
- set |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
- } else {
- clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
- }
+ if (have_armed == OK) {
+ if (armed.armed) {
+ set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
+ }
- /* Do not set failsafe if circuit breaker is enabled */
- if (armed.force_failsafe && !_cb_flighttermination) {
- set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
- } else {
- clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
- }
+ if (armed.lockdown && !_lockdown_override) {
+ set |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
+ }
- // XXX this is for future support in the commander
- // but can be removed if unneeded
- // if (armed.termination_failsafe) {
- // set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
- // } else {
- // clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
- // }
+ /* Do not set failsafe if circuit breaker is enabled */
+ if (armed.force_failsafe && !_cb_flighttermination) {
+ set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
+ }
- if (armed.ready_to_arm) {
- set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+ // XXX this is for future support in the commander
+ // but can be removed if unneeded
+ // if (armed.termination_failsafe) {
+ // set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // } else {
+ // clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // }
- } else {
- clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+ if (armed.ready_to_arm) {
+ set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+ }
}
- if (control_mode.flag_external_manual_override_ok) {
- set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
-
- } else {
- clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
+ if (have_control_mode == OK) {
+ if (control_mode.flag_external_manual_override_ok) {
+ set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
+ }
}
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
@@ -2193,7 +2200,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
if (pwm->channel_count > _max_actuators)
/* fail with error */
- return E2BIG;
+ return -E2BIG;
/* copy values to registers in IO */
ret = io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm->values, pwm->channel_count);
@@ -2212,7 +2219,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
if (pwm->channel_count > _max_actuators)
/* fail with error */
- return E2BIG;
+ return -E2BIG;
/* copy values to registers in IO */
ret = io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, pwm->values, pwm->channel_count);
@@ -2231,7 +2238,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
if (pwm->channel_count > _max_actuators)
/* fail with error */
- return E2BIG;
+ return -E2BIG;
/* copy values to registers in IO */
ret = io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, pwm->values, pwm->channel_count);
@@ -2250,7 +2257,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
if (pwm->channel_count > _max_actuators)
/* fail with error */
- return E2BIG;
+ return -E2BIG;
/* copy values to registers in IO */
ret = io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, pwm->values, pwm->channel_count);
@@ -2587,9 +2594,9 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
on param_get()
*/
struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
- if (config->channel >= _max_actuators) {
+ if (config->channel >= RC_INPUT_MAX_CHANNELS) {
/* fail with error */
- return E2BIG;
+ return -E2BIG;
}
/* copy values to registers in IO */
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
index 13cbfdfa8..d35722244 100644
--- a/src/drivers/rgbled/rgbled.cpp
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -121,7 +121,7 @@ private:
/* for now, we only support one RGBLED */
namespace
{
-RGBLED *g_rgbled;
+RGBLED *g_rgbled = nullptr;
}
void rgbled_usage();
@@ -680,15 +680,15 @@ rgbled_main(int argc, char *argv[])
ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_OFF);
close(fd);
+ /* delete the rgbled object if stop was requested, in addition to turning off the LED. */
+ if (!strcmp(verb, "stop")) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ exit(0);
+ }
exit(ret);
}
- if (!strcmp(verb, "stop")) {
- delete g_rgbled;
- g_rgbled = nullptr;
- exit(0);
- }
-
if (!strcmp(verb, "rgb")) {
if (argc < 5) {
errx(1, "Usage: rgbled rgb <red> <green> <blue>");
diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp
index 44ed03254..83086fd7c 100644
--- a/src/drivers/roboclaw/roboclaw_main.cpp
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -109,7 +109,7 @@ int roboclaw_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
2048,
roboclaw_thread_main,
- (const char **)argv);
+ (char * const *)argv);
exit(0);
} else if (!strcmp(argv[1], "test")) {
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 795d61704..8e62e0d4b 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -547,7 +547,7 @@ SF0X::collect()
float si_units;
bool valid = false;
-
+
for (int i = 0; i < ret; i++) {
if (OK == sf0x_parser(readbuf[i], _linebuf, &_linebuf_index, &_parse_state, &si_units)) {
valid = true;
@@ -566,6 +566,8 @@ SF0X::collect()
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
+ report.minimum_distance = get_minimum_distance();
+ report.maximum_distance = get_maximum_distance();
report.valid = valid && (si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0);
/* publish it */
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 281f918d7..603c2eb9d 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -253,9 +253,11 @@ static uint16_t latency_baseline;
static uint16_t latency_actual;
/* latency histogram */
-#define LATENCY_BUCKET_COUNT 8
-static const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
-static uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+#define LATENCY_BUCKET_COUNT 8
+__EXPORT const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
+__EXPORT const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
+__EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+
/* timer-specific functions */
static void hrt_tim_init(void);
diff --git a/src/drivers/trone/module.mk b/src/drivers/trone/module.mk
new file mode 100644
index 000000000..38499c6c3
--- /dev/null
+++ b/src/drivers/trone/module.mk
@@ -0,0 +1,44 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Makefile to build the TeraRanger One range finder driver
+#
+
+MODULE_COMMAND = trone
+
+SRCS = trone.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/trone/trone.cpp b/src/drivers/trone/trone.cpp
new file mode 100644
index 000000000..cf3546669
--- /dev/null
+++ b/src/drivers/trone/trone.cpp
@@ -0,0 +1,915 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file trone.cpp
+ * @author Luis Rodrigues
+ *
+ * Driver for the TeraRanger One range finders connected via I2C.
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.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 <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_range_finder.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <board_config.h>
+
+/* Configuration Constants */
+#define TRONE_BUS PX4_I2C_BUS_EXPANSION
+#define TRONE_BASEADDR 0x30 /* 7-bit address */
+#define TRONE_DEVICE_PATH "/dev/trone"
+
+/* TRONE Registers addresses */
+
+#define TRONE_MEASURE_REG 0x00 /* Measure range register */
+
+/* Device limits */
+#define TRONE_MIN_DISTANCE (0.20f)
+#define TRONE_MAX_DISTANCE (14.00f)
+
+#define TRONE_CONVERSION_INTERVAL 50000 /* 50ms */
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class TRONE : public device::I2C
+{
+public:
+ TRONE(int bus = TRONE_BUS, int address = TRONE_BASEADDR);
+ virtual ~TRONE();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+ float _min_distance;
+ float _max_distance;
+ work_s _work;
+ RingBuffer *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _class_instance;
+
+ orb_advert_t _range_finder_topic;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * 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.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Set the min and max distance thresholds if you want the end points of the sensors
+ * range to be brought in at all, otherwise it will use the defaults TRONE_MIN_DISTANCE
+ * and TRONE_MAX_DISTANCE
+ */
+ void set_minimum_distance(float min);
+ void set_maximum_distance(float max);
+ float get_minimum_distance();
+ float get_maximum_distance();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+ int measure();
+ int collect();
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+static const uint8_t crc_table[] = {
+ 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31,
+ 0x24, 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65,
+ 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9,
+ 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
+ 0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1,
+ 0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2,
+ 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe,
+ 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
+ 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16,
+ 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42,
+ 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80,
+ 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
+ 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8,
+ 0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c,
+ 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10,
+ 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
+ 0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f,
+ 0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b,
+ 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7,
+ 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
+ 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef,
+ 0xfa, 0xfd, 0xf4, 0xf3
+};
+
+static uint8_t crc8(uint8_t *p, uint8_t len) {
+ uint16_t i;
+ uint16_t crc = 0x0;
+
+ while (len--) {
+ i = (crc ^ *p++) & 0xFF;
+ crc = (crc_table[i] ^ (crc << 8)) & 0xFF;
+ }
+
+ return crc & 0xFF;
+}
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int trone_main(int argc, char *argv[]);
+
+TRONE::TRONE(int bus, int address) :
+ I2C("TRONE", TRONE_DEVICE_PATH, bus, address, 100000),
+ _min_distance(TRONE_MIN_DISTANCE),
+ _max_distance(TRONE_MAX_DISTANCE),
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _class_instance(-1),
+ _range_finder_topic(-1),
+ _sample_perf(perf_alloc(PC_ELAPSED, "trone_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "trone_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "trone_buffer_overflows"))
+{
+ // up the retries since the device misses the first measure attempts
+ I2C::_retries = 3;
+
+ // enable debug() calls
+ _debug_enabled = false;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+TRONE::~TRONE()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+
+ if (_class_instance != -1) {
+ unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
+ }
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
+}
+
+int
+TRONE::init()
+{
+ int ret = ERROR;
+
+ /* do I2C init (and probe) first */
+ if (I2C::init() != OK) {
+ goto out;
+ }
+
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(range_finder_report));
+
+ if (_reports == nullptr) {
+ goto out;
+ }
+
+ _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
+
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report rf_report;
+ measure();
+ _reports->get(&rf_report);
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
+
+ if (_range_finder_topic < 0) {
+ debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
+ }
+
+ ret = OK;
+ /* sensor is ok, but we don't really know if it is within range */
+ _sensor_ok = true;
+out:
+ return ret;
+}
+
+int
+TRONE::probe()
+{
+ return measure();
+}
+
+void
+TRONE::set_minimum_distance(float min)
+{
+ _min_distance = min;
+}
+
+void
+TRONE::set_maximum_distance(float max)
+{
+ _max_distance = max;
+}
+
+float
+TRONE::get_minimum_distance()
+{
+ return _min_distance;
+}
+
+float
+TRONE::get_maximum_distance()
+{
+ return _max_distance;
+}
+
+int
+TRONE::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(TRONE_CONVERSION_INTERVAL);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(TRONE_CONVERSION_INTERVAL)) {
+ return -EINVAL;
+ }
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0) {
+ return SENSOR_POLLRATE_MANUAL;
+ }
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _reports->size();
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ case RANGEFINDERIOCSETMINIUMDISTANCE: {
+ set_minimum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ case RANGEFINDERIOCSETMAXIUMDISTANCE: {
+ set_maximum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+TRONE::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct range_finder_report);
+ struct range_finder_report *rbuf = reinterpret_cast<struct range_finder_report *>(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1) {
+ return -ENOSPC;
+ }
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ do {
+ _reports->flush();
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(TRONE_CONVERSION_INTERVAL);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+int
+TRONE::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ const uint8_t cmd = TRONE_MEASURE_REG;
+ ret = transfer(&cmd, sizeof(cmd), nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ return ret;
+ }
+
+ ret = OK;
+
+ return ret;
+}
+
+int
+TRONE::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[3] = {0, 0, 0};
+
+ perf_begin(_sample_perf);
+
+ ret = transfer(nullptr, 0, &val[0], 3);
+
+ if (ret < 0) {
+ log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+ uint16_t distance = (val[0] << 8) | val[1];
+ float si_units = distance * 0.001f; /* mm to m */
+ struct range_finder_report report;
+
+ /* this should be fairly close to the end of the measurement, so the best approximation of the time */
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.distance = si_units;
+ report.minimum_distance = get_minimum_distance();
+ report.maximum_distance = get_maximum_distance();
+ report.valid = crc8(val, 2) == val[2] && si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
+
+
+ /* publish it, if we are the primary */
+ if (_range_finder_topic >= 0) {
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ }
+
+ if (_reports->force(&report)) {
+ perf_count(_buffer_overflows);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+ return ret;
+}
+
+void
+TRONE::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&TRONE::cycle_trampoline, this, 1);
+
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ true,
+ SUBSYSTEM_TYPE_RANGEFINDER
+ };
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+}
+
+void
+TRONE::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+TRONE::cycle_trampoline(void *arg)
+{
+ TRONE *dev = (TRONE *)arg;
+
+ dev->cycle();
+}
+
+void
+TRONE::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(TRONE_CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&TRONE::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(TRONE_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure()) {
+ log("measure error");
+ }
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&TRONE::cycle_trampoline,
+ this,
+ USEC2TICK(TRONE_CONVERSION_INTERVAL));
+}
+
+void
+TRONE::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ _reports->print_info("report queue");
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace trone
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+TRONE *g_dev;
+
+void start();
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ int fd;
+
+ if (g_dev != nullptr) {
+ errx(1, "already started");
+ }
+
+ /* create the driver */
+ g_dev = new TRONE(TRONE_BUS);
+
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ goto fail;
+ }
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(TRONE_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ goto fail;
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ goto fail;
+ }
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop()
+{
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ struct range_finder_report report;
+ ssize_t sz;
+ int ret;
+
+ int fd = open(TRONE_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "%s open failed (try 'trone start' if the driver is not running", TRONE_DEVICE_PATH);
+ }
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "immediate read failed");
+ }
+
+ warnx("single read");
+ warnx("measurement: %0.2f m", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
+ errx(1, "failed to set 2Hz poll rate");
+ }
+
+ /* read the sensor 50x and report each value */
+ for (unsigned i = 0; i < 50; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1) {
+ errx(1, "timed out waiting for sensor data");
+ }
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "periodic read failed");
+ }
+
+ warnx("periodic read %u", i);
+ warnx("valid %u", report.valid);
+ warnx("measurement: %0.3f", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+ }
+
+ /* reset the sensor polling to default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
+ errx(1, "failed to set default poll rate");
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(TRONE_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "failed ");
+ }
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
+ err(1, "driver reset failed");
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ err(1, "driver poll restart failed");
+ }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr) {
+ errx(1, "driver not running");
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+int
+trone_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start")) {
+ trone::start();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ trone::stop();
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test")) {
+ trone::test();
+ }
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset")) {
+ trone::reset();
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
+ trone::info();
+ }
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}