From dc600e7d65df3d91fc1dabac33b6e264ef9185df Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 20:58:47 +0200 Subject: First stab at IOCTL driven offset handling (in PA) for all airspeed sensors. Untested --- src/drivers/drv_airspeed.h | 9 +++++ src/drivers/ets_airspeed/ets_airspeed.cpp | 17 ++++++-- src/modules/sensors/sensor_params.c | 2 +- src/modules/sensors/sensors.cpp | 64 ++++++++++++++----------------- 4 files changed, 53 insertions(+), 39 deletions(-) diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h index bffc35c62..7bb9ee2af 100644 --- a/src/drivers/drv_airspeed.h +++ b/src/drivers/drv_airspeed.h @@ -57,5 +57,14 @@ #define _AIRSPEEDIOCBASE (0x7700) #define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n)) +#define AIRSPEEDIOCSSCALE __AIRSPEEDIOC(0) +#define AIRSPEEDIOCGSCALE __AIRSPEEDIOC(1) + + +/** airspeed scaling factors; out = (in * Vscale) + offset */ +struct airspeed_scale { + float offset_pa; + float scale; +}; #endif /* _DRV_AIRSPEED_H */ diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index b34d3fa5d..da449c195 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -129,7 +129,7 @@ private: bool _sensor_ok; int _measure_ticks; bool _collect_phase; - int _diff_pres_offset; + float _diff_pres_offset; orb_advert_t _airspeed_pub; @@ -358,6 +358,19 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg) /* XXX implement this */ return -EINVAL; + case AIRSPEEDIOCSSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + _diff_pres_offset = s->offset_pa; + return OK; + } + + case AIRSPEEDIOCGSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + s->offset_pa = _diff_pres_offset; + s->scale = 1.0f; + return OK; + } + default: /* give it to the superclass */ return I2C::ioctl(filp, cmd, arg); @@ -464,8 +477,6 @@ ETSAirspeed::collect() uint16_t diff_pres_pa = val[1] << 8 | val[0]; - // XXX move the parameter read out of the driver. - param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { diff_pres_pa = 0; diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index f6f4d60c7..57f1de1ac 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -68,7 +68,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); -PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667); +PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 1667); PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 1ded14a91..29f9de883 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -60,6 +60,7 @@ #include #include #include +#include #include #include @@ -199,7 +200,7 @@ private: float mag_scale[3]; float accel_offset[3]; float accel_scale[3]; - int diff_pres_offset_pa; + float diff_pres_offset_pa; int rc_type; @@ -230,6 +231,8 @@ private: float rc_scale_flaps; float battery_voltage_scaling; + + int airspeed_offset; } _parameters; /**< local copies of interesting parameters */ struct { @@ -278,6 +281,8 @@ private: param_t rc_scale_flaps; param_t battery_voltage_scaling; + + param_t airspeed_offset; } _parameter_handles; /**< handles for interesting parameters */ @@ -551,25 +556,11 @@ Sensors::parameters_update() /* rc values */ for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) { - if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) { - warnx("Failed getting min for chan %d", i); - } - - if (param_get(_parameter_handles.trim[i], &(_parameters.trim[i])) != OK) { - warnx("Failed getting trim for chan %d", i); - } - - if (param_get(_parameter_handles.max[i], &(_parameters.max[i])) != OK) { - warnx("Failed getting max for chan %d", i); - } - - if (param_get(_parameter_handles.rev[i], &(_parameters.rev[i])) != OK) { - warnx("Failed getting rev for chan %d", i); - } - - if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) { - warnx("Failed getting dead zone for chan %d", i); - } + param_get(_parameter_handles.min[i], &(_parameters.min[i])); + param_get(_parameter_handles.trim[i], &(_parameters.trim[i])); + param_get(_parameter_handles.max[i], &(_parameters.max[i])); + param_get(_parameter_handles.rev[i], &(_parameters.rev[i])); + param_get(_parameter_handles.dz[i], &(_parameters.dz[i])); _parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]); @@ -659,21 +650,10 @@ Sensors::parameters_update() warnx("Failed getting mode aux 5 index"); } - if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) { - warnx("Failed getting rc scaling for roll"); - } - - if (param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)) != OK) { - warnx("Failed getting rc scaling for pitch"); - } - - if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) { - warnx("Failed getting rc scaling for yaw"); - } - - if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) { - warnx("Failed getting rc scaling for flaps"); - } + param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)); + param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)); + param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)); + param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)); /* update RC function mappings */ _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; @@ -1033,6 +1013,20 @@ Sensors::parameter_update_poll(bool forced) close(fd); + fd = open(AIRSPEED_DEVICE_PATH, 0); + + /* this sensor is optional, abort without error */ + + if (fd > 0) { + struct airspeed_scale airscale = { + _parameters.diff_pres_offset_pa, + 1.0f, + }; + + if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) + warn("WARNING: failed to set scale / offsets for airspeed sensor"); + } + #if 0 printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]); printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]); -- cgit v1.2.3 From f87595a056e3688f5582d0315e161cceb16abc77 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 20:59:35 +0200 Subject: Minor initialization / formatting change --- src/drivers/ets_airspeed/ets_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index da449c195..0dbbfb4c3 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -196,7 +196,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), - _diff_pres_offset(0), + _diff_pres_offset(0.0f), _airspeed_pub(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")), _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")), -- cgit v1.2.3 From 290ca1f9bf973a9ef957cb413930f7aac06054e4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 21:45:59 +0200 Subject: Reworked airspeed driver to keep most of it abstract --- makefiles/config_px4fmu-v1_default.mk | 2 + src/drivers/airspeed/airspeed.cpp | 378 ++++++++++++++++++++++ src/drivers/airspeed/airspeed.h | 169 ++++++++++ src/drivers/airspeed/module.mk | 38 +++ src/drivers/ets_airspeed/ets_airspeed.cpp | 398 +---------------------- src/drivers/meas_airspeed/meas_airspeed.cpp | 482 ++++++++++++++++++++++++++++ src/drivers/meas_airspeed/module.mk | 41 +++ 7 files changed, 1124 insertions(+), 384 deletions(-) create mode 100644 src/drivers/airspeed/airspeed.cpp create mode 100644 src/drivers/airspeed/airspeed.h create mode 100644 src/drivers/airspeed/module.mk create mode 100644 src/drivers/meas_airspeed/meas_airspeed.cpp create mode 100644 src/drivers/meas_airspeed/module.mk diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 213eb651b..a769eb8f2 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -31,7 +31,9 @@ MODULES += drivers/hott_telemetry MODULES += drivers/blinkm MODULES += drivers/mkblctrl MODULES += drivers/md25 +MODULES += drivers/airspeed MODULES += drivers/ets_airspeed +MODULES += drivers/meas_airspeed MODULES += modules/sensors # diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp new file mode 100644 index 000000000..2c719928a --- /dev/null +++ b/src/drivers/airspeed/airspeed.cpp @@ -0,0 +1,378 @@ +/**************************************************************************** + * + * 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 ets_airspeed.cpp + * @author Simon Wilks + * + * Driver for the Eagle Tree Airspeed V3 connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include + +Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) : + I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), + _num_reports(0), + _next_report(0), + _oldest_report(0), + _reports(nullptr), + _sensor_ok(false), + _measure_ticks(0), + _collect_phase(false), + _diff_pres_offset(0.0f), + _airspeed_pub(-1), + _conversion_interval(conversion_interval), + _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")), + _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")) +{ + // enable debug() calls + _debug_enabled = true; + + // work_cancel in the dtor will explode if we don't do this... + memset(&_work, 0, sizeof(_work)); +} + +Airspeed::~Airspeed() +{ + /* make sure we are truly inactive */ + stop(); + + /* free any existing reports */ + if (_reports != nullptr) + delete[] _reports; +} + +int +Airspeed::init() +{ + int ret = ERROR; + + /* do I2C init (and probe) first */ + if (I2C::init() != OK) + goto out; + + /* allocate basic report buffers */ + _num_reports = 2; + _reports = new struct differential_pressure_s[_num_reports]; + + for (unsigned i = 0; i < _num_reports; i++) + _reports[i].max_differential_pressure_pa = 0; + + if (_reports == nullptr) + goto out; + + _oldest_report = _next_report = 0; + + /* get a publish handle on the airspeed topic */ + memset(&_reports[0], 0, sizeof(_reports[0])); + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); + + if (_airspeed_pub < 0) + debug("failed to create airspeed sensor 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 +Airspeed::probe() +{ + return measure(); +} + +int +Airspeed::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(_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(_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: { + /* add one to account for the sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct differential_pressure_s *buf = new struct differential_pressure_s[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _reports; + _num_reports = arg; + _reports = buf; + start(); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _num_reports - 1; + + case SENSORIOCRESET: + /* XXX implement this */ + return -EINVAL; + + case AIRSPEEDIOCSSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + _diff_pres_offset = s->offset_pa; + return OK; + } + + case AIRSPEEDIOCGSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + s->offset_pa = _diff_pres_offset; + s->scale = 1.0f; + return OK; + } + + default: + /* give it to the superclass */ + return I2C::ioctl(filp, cmd, arg); + } +} + +ssize_t +Airspeed::read(struct file *filp, char *buffer, size_t buflen) +{ + unsigned count = buflen / sizeof(struct differential_pressure_s); + 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 (_oldest_report != _next_report) { + memcpy(buffer, _reports + _oldest_report, sizeof(*_reports)); + ret += sizeof(_reports[0]); + INCREMENT(_oldest_report, _num_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement - run one conversion */ + /* XXX really it'd be nice to lock against other readers here */ + do { + _oldest_report = _next_report = 0; + + /* trigger a measurement */ + if (OK != measure()) { + ret = -EIO; + break; + } + + /* wait for it to complete */ + usleep(_conversion_interval); + + /* run the collection phase */ + if (OK != collect()) { + ret = -EIO; + break; + } + + /* state machine will have generated a report, copy it out */ + memcpy(buffer, _reports, sizeof(*_reports)); + ret = sizeof(*_reports); + + } while (0); + + return ret; +} + +void +Airspeed::start() +{ + /* reset the report ring and state machine */ + _collect_phase = false; + _oldest_report = _next_report = 0; + + /* schedule a cycle to start things */ + work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1); + + /* notify about state change */ + struct subsystem_info_s info = { + true, + true, + true, + SUBSYSTEM_TYPE_DIFFPRESSURE + }; + 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 +Airspeed::stop() +{ + work_cancel(HPWORK, &_work); +} + +void +Airspeed::cycle_trampoline(void *arg) +{ + Airspeed *dev = (Airspeed *)arg; + + dev->cycle(); +} + +void +Airspeed::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); + perf_print_counter(_buffer_overflows); + warnx("poll interval: %u ticks", _measure_ticks); + warnx("report queue: %u (%u/%u @ %p)", + _num_reports, _oldest_report, _next_report, _reports); +} diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h new file mode 100644 index 000000000..3cc03ede9 --- /dev/null +++ b/src/drivers/airspeed/airspeed.h @@ -0,0 +1,169 @@ +/**************************************************************************** + * + * 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 airspeed.h + * @author Simon Wilks + * + * Generic driver for airspeed sensors connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +/* Default I2C bus */ +#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION + +/* 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 Airspeed : public device::I2C +{ +public: + Airspeed(int bus, int address, unsigned conversion_interval); + virtual ~Airspeed(); + + 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(); + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + virtual void cycle() = 0; + virtual int measure() = 0; + virtual int collect() = 0; + + work_s _work; + unsigned _num_reports; + volatile unsigned _next_report; + volatile unsigned _oldest_report; + differential_pressure_s *_reports; + bool _sensor_ok; + int _measure_ticks; + bool _collect_phase; + float _diff_pres_offset; + + orb_advert_t _airspeed_pub; + + unsigned _conversion_interval; + + 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(); + + /** + * 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); + +}; + +/* helper macro for handling report buffer indices */ +#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) + diff --git a/src/drivers/airspeed/module.mk b/src/drivers/airspeed/module.mk new file mode 100644 index 000000000..4eef06161 --- /dev/null +++ b/src/drivers/airspeed/module.mk @@ -0,0 +1,38 @@ +############################################################################ +# +# 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. +# +############################################################################ + +# +# Makefile to build the generic airspeed driver. +# + +SRCS = airspeed.cpp diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 0dbbfb4c3..3e3930715 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -72,9 +72,7 @@ #include #include #include - -/* Default I2C bus */ -#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION +#include /* I2C bus address */ #define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ @@ -91,349 +89,33 @@ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ -/* 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 ETSAirspeed : public device::I2C +class ETSAirspeed : public Airspeed { public: ETSAirspeed(int bus, int address = I2C_ADDRESS); virtual ~ETSAirspeed(); - 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: - work_s _work; - unsigned _num_reports; - volatile unsigned _next_report; - volatile unsigned _oldest_report; - differential_pressure_s *_reports; - bool _sensor_ok; - int _measure_ticks; - bool _collect_phase; - float _diff_pres_offset; - - orb_advert_t _airspeed_pub; - - 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(); /** * 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); - + virtual void cycle(); + virtual int measure(); + virtual int collect(); }; -/* helper macro for handling report buffer indices */ -#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) - /* * Driver 'main' command. */ extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]); -ETSAirspeed::ETSAirspeed(int bus, int address) : - I2C("ETSAirspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), - _num_reports(0), - _next_report(0), - _oldest_report(0), - _reports(nullptr), - _sensor_ok(false), - _measure_ticks(0), - _collect_phase(false), - _diff_pres_offset(0.0f), - _airspeed_pub(-1), - _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")), - _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ets_airspeed_buffer_overflows")) -{ - // enable debug() calls - _debug_enabled = true; - - // work_cancel in the dtor will explode if we don't do this... - memset(&_work, 0, sizeof(_work)); -} - -ETSAirspeed::~ETSAirspeed() -{ - /* make sure we are truly inactive */ - stop(); - - /* free any existing reports */ - if (_reports != nullptr) - delete[] _reports; -} - -int -ETSAirspeed::init() -{ - int ret = ERROR; - - /* do I2C init (and probe) first */ - if (I2C::init() != OK) - goto out; - - /* allocate basic report buffers */ - _num_reports = 2; - _reports = new struct differential_pressure_s[_num_reports]; - - for (unsigned i = 0; i < _num_reports; i++) - _reports[i].max_differential_pressure_pa = 0; - - if (_reports == nullptr) - goto out; - - _oldest_report = _next_report = 0; - - /* get a publish handle on the airspeed topic */ - memset(&_reports[0], 0, sizeof(_reports[0])); - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); - - if (_airspeed_pub < 0) - debug("failed to create airspeed sensor 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 -ETSAirspeed::probe() -{ - return measure(); -} - -int -ETSAirspeed::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(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(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: { - /* add one to account for the sentinel in the ring */ - arg++; - - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) - return -EINVAL; - - /* allocate new buffer */ - struct differential_pressure_s *buf = new struct differential_pressure_s[arg]; - - if (nullptr == buf) - return -ENOMEM; - - /* reset the measurement state machine with the new buffer, free the old */ - stop(); - delete[] _reports; - _num_reports = arg; - _reports = buf; - start(); - - return OK; - } - - case SENSORIOCGQUEUEDEPTH: - return _num_reports - 1; - - case SENSORIOCRESET: - /* XXX implement this */ - return -EINVAL; - - case AIRSPEEDIOCSSCALE: { - struct airspeed_scale *s = (struct airspeed_scale*)arg; - _diff_pres_offset = s->offset_pa; - return OK; - } - - case AIRSPEEDIOCGSCALE: { - struct airspeed_scale *s = (struct airspeed_scale*)arg; - s->offset_pa = _diff_pres_offset; - s->scale = 1.0f; - return OK; - } - - default: - /* give it to the superclass */ - return I2C::ioctl(filp, cmd, arg); - } -} - -ssize_t -ETSAirspeed::read(struct file *filp, char *buffer, size_t buflen) +ETSAirspeed::ETSAirspeed(int bus, int address) : Airspeed(bus, address, + CONVERSION_INTERVAL) { - unsigned count = buflen / sizeof(struct differential_pressure_s); - 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 (_oldest_report != _next_report) { - memcpy(buffer, _reports + _oldest_report, sizeof(*_reports)); - ret += sizeof(_reports[0]); - INCREMENT(_oldest_report, _num_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; - } - - /* manual measurement - run one conversion */ - /* XXX really it'd be nice to lock against other readers here */ - do { - _oldest_report = _next_report = 0; - - /* trigger a measurement */ - if (OK != measure()) { - ret = -EIO; - break; - } - - /* wait for it to complete */ - usleep(CONVERSION_INTERVAL); - - /* run the collection phase */ - if (OK != collect()) { - ret = -EIO; - break; - } - - /* state machine will have generated a report, copy it out */ - memcpy(buffer, _reports, sizeof(*_reports)); - ret = sizeof(*_reports); - } while (0); - - return ret; } int @@ -516,47 +198,6 @@ ETSAirspeed::collect() return ret; } -void -ETSAirspeed::start() -{ - /* reset the report ring and state machine */ - _collect_phase = false; - _oldest_report = _next_report = 0; - - /* schedule a cycle to start things */ - work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1); - - /* notify about state change */ - struct subsystem_info_s info = { - true, - true, - true, - SUBSYSTEM_TYPE_DIFFPRESSURE - }; - 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 -ETSAirspeed::stop() -{ - work_cancel(HPWORK, &_work); -} - -void -ETSAirspeed::cycle_trampoline(void *arg) -{ - ETSAirspeed *dev = (ETSAirspeed *)arg; - - dev->cycle(); -} - void ETSAirspeed::cycle() { @@ -582,7 +223,7 @@ ETSAirspeed::cycle() /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, - (worker_t)&ETSAirspeed::cycle_trampoline, + (worker_t)&Airspeed::cycle_trampoline, this, _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); @@ -600,22 +241,11 @@ ETSAirspeed::cycle() /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, &_work, - (worker_t)&ETSAirspeed::cycle_trampoline, + (worker_t)&Airspeed::cycle_trampoline, this, USEC2TICK(CONVERSION_INTERVAL)); } -void -ETSAirspeed::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); - printf("report queue: %u (%u/%u @ %p)\n", - _num_reports, _oldest_report, _next_report, _reports); -} - /** * Local functions in support of the shell command. */ @@ -790,11 +420,11 @@ info() static void ets_airspeed_usage() { - fprintf(stderr, "usage: ets_airspeed command [options]\n"); - fprintf(stderr, "options:\n"); - fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT); - fprintf(stderr, "command:\n"); - fprintf(stderr, "\tstart|stop|reset|test|info\n"); + warnx("usage: ets_airspeed command [options]"); + warnx("options:"); + warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT); + warnx("command:"); + warnx("\tstart|stop|reset|test|info"); } int diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp new file mode 100644 index 000000000..4fa02a20b --- /dev/null +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -0,0 +1,482 @@ +/**************************************************************************** + * + * 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 meas_airspeed.cpp + * @author Lorenz Meier + * @author Simon Wilks + * + * Driver for the MEAS Spec series connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include + +/* Default I2C bus */ +#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION + +/* I2C bus address */ +#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ + +/* Register address */ +#define READ_CMD 0x07 /* Read the data */ + +/** + * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. + * You can set this value to 12 if you want a zero reading below 15km/h. + */ +#define MIN_ACCURATE_DIFF_PRES_PA 0 + +/* Measurement rate is 100Hz */ +#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ + +class MEASAirspeed : public Airspeed +{ +public: + MEASAirspeed(int bus, int address = I2C_ADDRESS); + virtual ~MEASAirspeed(); + +protected: + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + virtual void cycle(); + virtual int measure(); + virtual int collect(); + +}; + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); + +MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, + CONVERSION_INTERVAL) +{ + +} + +int +MEASAirspeed::measure() +{ + int ret; + + /* + * Send the command to begin a measurement. + */ + uint8_t cmd = READ_CMD; + ret = transfer(&cmd, 1, nullptr, 0); + + if (OK != ret) { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } + + ret = OK; + + return ret; +} + +int +MEASAirspeed::collect() +{ + int ret = -EIO; + + /* read from the sensor */ + uint8_t val[2] = {0, 0}; + + perf_begin(_sample_perf); + + ret = transfer(nullptr, 0, &val[0], 2); + + if (ret < 0) { + log("error reading from sensor: %d", ret); + return ret; + } + + uint16_t diff_pres_pa = val[1] << 8 | val[0]; + + if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + diff_pres_pa = 0; + + } else { + diff_pres_pa -= _diff_pres_offset; + } + + // XXX we may want to smooth out the readings to remove noise. + + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].differential_pressure_pa = diff_pres_pa; + + // Track maximum differential pressure measured (so we can work out top speed). + if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + } + + /* announce the airspeed if needed, just publish else */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + + /* post a report to the ring - note, not locked */ + INCREMENT(_next_report, _num_reports); + + /* if we are running up against the oldest report, toss it */ + if (_next_report == _oldest_report) { + perf_count(_buffer_overflows); + INCREMENT(_oldest_report, _num_reports); + } + + /* notify anyone waiting for data */ + poll_notify(POLLIN); + + ret = OK; + + perf_end(_sample_perf); + + return ret; +} + +void +MEASAirspeed::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(CONVERSION_INTERVAL)) { + + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&Airspeed::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(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)&Airspeed::cycle_trampoline, + this, + USEC2TICK(CONVERSION_INTERVAL)); +} + +/** + * Local functions in support of the shell command. + */ +namespace meas_airspeed +{ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +const int ERROR = -1; + +MEASAirspeed *g_dev; + +void start(int i2c_bus); +void stop(); +void test(); +void reset(); +void info(); + +/** + * Start the driver. + */ +void +start(int i2c_bus) +{ + int fd; + + if (g_dev != nullptr) + errx(1, "already started"); + + /* create the driver */ + g_dev = new MEASAirspeed(i2c_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(AIRSPEED_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 differential_pressure_s report; + ssize_t sz; + int ret; + + int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "%s open failed (try 'meas_airspeed start' if the driver is not running", AIRSPEED_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("diff pressure: %d pa", report.differential_pressure_pa); + + /* start the sensor polling at 2Hz */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) + errx(1, "failed to set 2Hz poll rate"); + + /* read the sensor 5x and report each value */ + for (unsigned i = 0; i < 5; 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("diff pressure: %d pa", report.differential_pressure_pa); + } + + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = open(AIRSPEED_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 + + +static void +meas_airspeed_usage() +{ + warnx("usage: meas_airspeed command [options]"); + warnx("options:"); + warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT); + warnx("command:"); + warnx("\tstart|stop|reset|test|info"); +} + +int +meas_airspeed_main(int argc, char *argv[]) +{ + int i2c_bus = PX4_I2C_BUS_DEFAULT; + + int i; + + for (i = 1; i < argc; i++) { + if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { + if (argc > i + 1) { + i2c_bus = atoi(argv[i + 1]); + } + } + } + + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) + meas_airspeed::start(i2c_bus); + + /* + * Stop the driver + */ + if (!strcmp(argv[1], "stop")) + meas_airspeed::stop(); + + /* + * Test the driver/device. + */ + if (!strcmp(argv[1], "test")) + meas_airspeed::test(); + + /* + * Reset the driver. + */ + if (!strcmp(argv[1], "reset")) + meas_airspeed::reset(); + + /* + * Print driver information. + */ + if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) + meas_airspeed::info(); + + meas_airspeed_usage(); + exit(0); +} diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk new file mode 100644 index 000000000..ddcd54351 --- /dev/null +++ b/src/drivers/meas_airspeed/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# 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. +# +############################################################################ + +# +# Makefile to build the MEAS Spec airspeed sensor driver. +# + +MODULE_COMMAND = meas_airspeed +MODULE_STACKSIZE = 1024 + +SRCS = meas_airspeed.cpp -- cgit v1.2.3 From 7fe2aa27974f93810727b0a59658ed760c6ad591 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 14 Jul 2013 11:22:20 +0200 Subject: Fixed last few compile errors, ready for testing --- src/drivers/airspeed/airspeed.cpp | 2 +- src/drivers/airspeed/airspeed.h | 4 +- src/drivers/ets_airspeed/ets_airspeed.cpp | 1 - src/drivers/meas_airspeed/meas_airspeed.cpp | 203 +++++++++++++++------------- 4 files changed, 115 insertions(+), 95 deletions(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 2c719928a..5a8157deb 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -134,7 +134,7 @@ Airspeed::init() _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); if (_airspeed_pub < 0) - debug("failed to create airspeed sensor object. Did you start uOrb?"); + warnx("failed to create airspeed sensor object. Did you start uOrb?"); ret = OK; /* sensor is ok, but we don't really know if it is within range */ diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h index 3cc03ede9..89dfb22d7 100644 --- a/src/drivers/airspeed/airspeed.h +++ b/src/drivers/airspeed/airspeed.h @@ -86,7 +86,7 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -class Airspeed : public device::I2C +class __EXPORT Airspeed : public device::I2C { public: Airspeed(int bus, int address, unsigned conversion_interval); @@ -100,7 +100,7 @@ public: /** * Diagnostics - print some basic information about the driver. */ - void print_info(); + virtual void print_info(); protected: virtual int probe(); diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 3e3930715..a24bd78a5 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -93,7 +93,6 @@ class ETSAirspeed : public Airspeed { public: ETSAirspeed(int bus, int address = I2C_ADDRESS); - virtual ~ETSAirspeed(); protected: diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 4fa02a20b..0c9142d63 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -37,6 +37,15 @@ * @author Simon Wilks * * Driver for the MEAS Spec series connected via I2C. + * + * Supported sensors: + * + * - MS4525DO (http://www.meas-spec.com/downloads/MS4525DO.pdf) + * - untested: MS5525DSO (http://www.meas-spec.com/downloads/MS5525DSO.pdf) + * + * Interface application notes: + * + * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/application-notes.aspx#) */ #include @@ -79,8 +88,10 @@ /* Default I2C bus */ #define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION -/* I2C bus address */ -#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ +/* I2C bus address is 1010001x */ +#define I2C_ADDRESS_MS4525DO 0x51 /* 7-bit address. */ +/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ +#define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ /* Register address */ #define READ_CMD 0x07 /* Read the data */ @@ -97,8 +108,7 @@ class MEASAirspeed : public Airspeed { public: - MEASAirspeed(int bus, int address = I2C_ADDRESS); - virtual ~MEASAirspeed(); + MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO); protected: @@ -126,122 +136,122 @@ MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, int MEASAirspeed::measure() { - int ret; + // int ret; - /* - * Send the command to begin a measurement. - */ - uint8_t cmd = READ_CMD; - ret = transfer(&cmd, 1, nullptr, 0); + // /* + // * Send the command to begin a measurement. + // */ + // uint8_t cmd = READ_CMD; + // ret = transfer(&cmd, 1, nullptr, 0); - if (OK != ret) { - perf_count(_comms_errors); - log("i2c::transfer returned %d", ret); - return ret; - } + // if (OK != ret) { + // perf_count(_comms_errors); + // log("i2c::transfer returned %d", ret); + // return ret; + // } - ret = OK; + // ret = OK; - return ret; + // return ret; } int MEASAirspeed::collect() { - int ret = -EIO; + // int ret = -EIO; - /* read from the sensor */ - uint8_t val[2] = {0, 0}; + // /* read from the sensor */ + // uint8_t val[2] = {0, 0}; - perf_begin(_sample_perf); + // perf_begin(_sample_perf); - ret = transfer(nullptr, 0, &val[0], 2); + // ret = transfer(nullptr, 0, &val[0], 2); - if (ret < 0) { - log("error reading from sensor: %d", ret); - return ret; - } + // if (ret < 0) { + // log("error reading from sensor: %d", ret); + // return ret; + // } - uint16_t diff_pres_pa = val[1] << 8 | val[0]; + // uint16_t diff_pres_pa = val[1] << 8 | val[0]; - if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - diff_pres_pa = 0; + // if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + // diff_pres_pa = 0; - } else { - diff_pres_pa -= _diff_pres_offset; - } + // } else { + // diff_pres_pa -= _diff_pres_offset; + // } - // XXX we may want to smooth out the readings to remove noise. + // // XXX we may want to smooth out the readings to remove noise. - _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].differential_pressure_pa = diff_pres_pa; + // _reports[_next_report].timestamp = hrt_absolute_time(); + // _reports[_next_report].differential_pressure_pa = diff_pres_pa; - // Track maximum differential pressure measured (so we can work out top speed). - if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; - } + // // Track maximum differential pressure measured (so we can work out top speed). + // if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + // _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + // } - /* announce the airspeed if needed, just publish else */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + // /* announce the airspeed if needed, just publish else */ + // orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); - /* post a report to the ring - note, not locked */ - INCREMENT(_next_report, _num_reports); + // /* post a report to the ring - note, not locked */ + // INCREMENT(_next_report, _num_reports); - /* if we are running up against the oldest report, toss it */ - if (_next_report == _oldest_report) { - perf_count(_buffer_overflows); - INCREMENT(_oldest_report, _num_reports); - } + // /* if we are running up against the oldest report, toss it */ + // if (_next_report == _oldest_report) { + // perf_count(_buffer_overflows); + // INCREMENT(_oldest_report, _num_reports); + // } - /* notify anyone waiting for data */ - poll_notify(POLLIN); + // /* notify anyone waiting for data */ + // poll_notify(POLLIN); - ret = OK; + // ret = OK; - perf_end(_sample_perf); + // perf_end(_sample_perf); - return ret; + // return ret; } void MEASAirspeed::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(CONVERSION_INTERVAL)) { - - /* schedule a fresh cycle call when we are ready to measure again */ - work_queue(HPWORK, - &_work, - (worker_t)&Airspeed::cycle_trampoline, - this, - _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); - - return; - } - } - - /* measurement phase */ - if (OK != measure()) - log("measure error"); - - /* next phase is collection */ - _collect_phase = true; + // /* 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(CONVERSION_INTERVAL)) { + + // /* schedule a fresh cycle call when we are ready to measure again */ + // work_queue(HPWORK, + // &_work, + // (worker_t)&Airspeed::cycle_trampoline, + // this, + // _measure_ticks - USEC2TICK(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, @@ -282,12 +292,23 @@ start(int i2c_bus) if (g_dev != nullptr) errx(1, "already started"); - /* create the driver */ - g_dev = new MEASAirspeed(i2c_bus); + /* create the driver, try the MS4525DO first */ + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + + /* check if the MS4525DO was instantiated */ + if (g_dev == nullptr) + goto fail; + + /* try the MS5525DSO next if init fails */ + if (OK != g_dev->init()) + delete g_dev; + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); + /* check if the MS5525DSO was instantiated */ if (g_dev == nullptr) goto fail; + /* both versions failed if the init for the MS5525DSO fails, give up */ if (OK != g_dev->init()) goto fail; -- cgit v1.2.3 From 08ddbbc23e5ee40c95cc838c08e946c7ac063698 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 14 Jul 2013 21:12:09 +0200 Subject: WIP on MEAS bringup, ETS airspeed sensors should be operational --- src/drivers/meas_airspeed/meas_airspeed.cpp | 208 +++++++++++++++++----------- 1 file changed, 124 insertions(+), 84 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 0c9142d63..6603d3452 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -45,7 +45,7 @@ * * Interface application notes: * - * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/application-notes.aspx#) + * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf) */ #include @@ -94,7 +94,12 @@ #define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ /* Register address */ -#define READ_CMD 0x07 /* Read the data */ +#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ +#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */ +#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */ +#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */ +#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ +#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */ /** * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. @@ -136,122 +141,122 @@ MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, int MEASAirspeed::measure() { - // int ret; - - // /* - // * Send the command to begin a measurement. - // */ - // uint8_t cmd = READ_CMD; - // ret = transfer(&cmd, 1, nullptr, 0); - - // if (OK != ret) { - // perf_count(_comms_errors); - // log("i2c::transfer returned %d", ret); - // return ret; - // } + int ret; + + /* + * Send the command to begin a measurement. + */ + uint8_t cmd = ADDR_RESET_CMD; + ret = transfer(&cmd, 1, nullptr, 0); + + if (OK != ret) { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } - // ret = OK; + ret = OK; - // return ret; + return ret; } int MEASAirspeed::collect() { - // int ret = -EIO; + int ret = -EIO; - // /* read from the sensor */ - // uint8_t val[2] = {0, 0}; + /* read from the sensor */ + uint8_t val[2] = {0, 0}; - // perf_begin(_sample_perf); + perf_begin(_sample_perf); - // ret = transfer(nullptr, 0, &val[0], 2); + ret = transfer(nullptr, 0, &val[0], 2); - // if (ret < 0) { - // log("error reading from sensor: %d", ret); - // return ret; - // } + if (ret < 0) { + log("error reading from sensor: %d", ret); + return ret; + } - // uint16_t diff_pres_pa = val[1] << 8 | val[0]; + uint16_t diff_pres_pa = val[1] << 8 | val[0]; - // if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - // diff_pres_pa = 0; + if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + diff_pres_pa = 0; - // } else { - // diff_pres_pa -= _diff_pres_offset; - // } + } else { + diff_pres_pa -= _diff_pres_offset; + } - // // XXX we may want to smooth out the readings to remove noise. + // XXX we may want to smooth out the readings to remove noise. - // _reports[_next_report].timestamp = hrt_absolute_time(); - // _reports[_next_report].differential_pressure_pa = diff_pres_pa; + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].differential_pressure_pa = diff_pres_pa; - // // Track maximum differential pressure measured (so we can work out top speed). - // if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - // _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; - // } + // Track maximum differential pressure measured (so we can work out top speed). + if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + } - // /* announce the airspeed if needed, just publish else */ - // orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + /* announce the airspeed if needed, just publish else */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); - // /* post a report to the ring - note, not locked */ - // INCREMENT(_next_report, _num_reports); + /* post a report to the ring - note, not locked */ + INCREMENT(_next_report, _num_reports); - // /* if we are running up against the oldest report, toss it */ - // if (_next_report == _oldest_report) { - // perf_count(_buffer_overflows); - // INCREMENT(_oldest_report, _num_reports); - // } + /* if we are running up against the oldest report, toss it */ + if (_next_report == _oldest_report) { + perf_count(_buffer_overflows); + INCREMENT(_oldest_report, _num_reports); + } - // /* notify anyone waiting for data */ - // poll_notify(POLLIN); + /* notify anyone waiting for data */ + poll_notify(POLLIN); - // ret = OK; + ret = OK; - // perf_end(_sample_perf); + perf_end(_sample_perf); - // return ret; + return ret; } void MEASAirspeed::cycle() { - // /* collection phase? */ - // if (_collect_phase) { - - // /* perform collection */ - // if (OK != collect()) { - // log("collection error"); - // /* restart the measurement state machine */ - // start(); - // return; - // } + /* 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; + /* next phase is measurement */ + _collect_phase = false; - // /* - // * Is there a collect->measure gap? - // */ - // if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { + /* + * Is there a collect->measure gap? + */ + if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { - // /* schedule a fresh cycle call when we are ready to measure again */ - // work_queue(HPWORK, - // &_work, - // (worker_t)&Airspeed::cycle_trampoline, - // this, - // _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&Airspeed::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); - // return; - // } - // } + return; + } + } - // /* measurement phase */ - // if (OK != measure()) - // log("measure error"); + /* measurement phase */ + if (OK != measure()) + log("measure error"); - // /* next phase is collection */ - // _collect_phase = true; + /* next phase is collection */ + _collect_phase = true; /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, @@ -293,7 +298,42 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver, try the MS4525DO first */ - g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + + { + int bus = PX4_I2C_BUS_EXPANSION; + //delete g_dev; + + // XXX hack scan all addresses + for (int i = 1; i < 0xFF / 2; i++) { + warnx("scanning addr (7 bit): %0x", i); + g_dev = new MEASAirspeed(bus, i); + warnx("probing"); + if (OK == g_dev->init()) { + warnx("SUCCESS!"); + exit(0); + } else { + delete g_dev; + } + + } + + // bus = PX4_I2C_BUS_ESC; + + // for (int i = 1; i < 0xFF / 2; i++) { + // warnx("scanning addr (7 bit): %0x", i); + // g_dev = new MEASAirspeed(bus, i); + // if (OK == g_dev->init()) { + // warnx("SUCCESS!"); + // exit(0); + // } else { + // delete g_dev; + // } + + // } + + exit(1); +} /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) -- cgit v1.2.3 From 97f732ccf1e05f55ae2e48ef9d21c8e9b7b57510 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 22 Jul 2013 09:19:59 +0200 Subject: Fixed up ets driver (not tested, WIP on meas driver) --- src/drivers/ets_airspeed/ets_airspeed.cpp | 2 +- src/drivers/meas_airspeed/meas_airspeed.cpp | 42 ++++++++++++++--------------- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index a24bd78a5..2e32ed334 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -282,7 +282,7 @@ start(int i2c_bus) if (g_dev == nullptr) goto fail; - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) goto fail; /* set the poll rate to default, starts automatic data collection */ diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 6603d3452..f31dc857d 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -278,7 +278,7 @@ namespace meas_airspeed #endif const int ERROR = -1; -MEASAirspeed *g_dev; +MEASAirspeed *g_dev = nullptr; void start(int i2c_bus); void stop(); @@ -300,47 +300,47 @@ start(int i2c_bus) /* create the driver, try the MS4525DO first */ //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); - { + int bus = PX4_I2C_BUS_EXPANSION; //delete g_dev; // XXX hack scan all addresses - for (int i = 1; i < 0xFF / 2; i++) { - warnx("scanning addr (7 bit): %0x", i); + for (int i = 0x20 / 2; i < 0xFE / 2; i++) { + warnx("scanning addr (7 bit): 0x%02x", i); g_dev = new MEASAirspeed(bus, i); warnx("probing"); - if (OK == g_dev->init()) { + if (OK == g_dev->Airspeed::init()) { warnx("SUCCESS!"); + usleep(200000); exit(0); } else { + warnx("FAIL!"); + usleep(200000); delete g_dev; } } - // bus = PX4_I2C_BUS_ESC; + bus = PX4_I2C_BUS_ESC; - // for (int i = 1; i < 0xFF / 2; i++) { - // warnx("scanning addr (7 bit): %0x", i); - // g_dev = new MEASAirspeed(bus, i); - // if (OK == g_dev->init()) { - // warnx("SUCCESS!"); - // exit(0); - // } else { - // delete g_dev; - // } - - // } + for (int i = 1; i < 0xFF / 2; i++) { + warnx("scanning addr (7 bit): %0x", i); + g_dev = new MEASAirspeed(bus, i); + if (OK == g_dev->Airspeed::init()) { + warnx("SUCCESS!"); + exit(0); + } else { + delete g_dev; + } - exit(1); -} + } /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) goto fail; /* try the MS5525DSO next if init fails */ - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) delete g_dev; g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); @@ -349,7 +349,7 @@ start(int i2c_bus) goto fail; /* both versions failed if the init for the MS5525DSO fails, give up */ - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) goto fail; /* set the poll rate to default, starts automatic data collection */ -- cgit v1.2.3 From edcd25b5ed15502b32c9dadc1fbbbfa552f0b74f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 22 Jul 2013 10:24:35 +0200 Subject: Airspeed sensor driver operational, needs cleanup / testing --- src/drivers/meas_airspeed/meas_airspeed.cpp | 59 ++++++----------------------- 1 file changed, 11 insertions(+), 48 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index f31dc857d..5dcc97e6f 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -85,13 +85,10 @@ #include -/* Default I2C bus */ -#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION - /* I2C bus address is 1010001x */ -#define I2C_ADDRESS_MS4525DO 0x51 /* 7-bit address. */ +#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */ /* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ -#define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ +#define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ /* Register address */ #define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ @@ -298,59 +295,25 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver, try the MS4525DO first */ - //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); - - - int bus = PX4_I2C_BUS_EXPANSION; - //delete g_dev; - - // XXX hack scan all addresses - for (int i = 0x20 / 2; i < 0xFE / 2; i++) { - warnx("scanning addr (7 bit): 0x%02x", i); - g_dev = new MEASAirspeed(bus, i); - warnx("probing"); - if (OK == g_dev->Airspeed::init()) { - warnx("SUCCESS!"); - usleep(200000); - exit(0); - } else { - warnx("FAIL!"); - usleep(200000); - delete g_dev; - } - - } - - bus = PX4_I2C_BUS_ESC; - - for (int i = 1; i < 0xFF / 2; i++) { - warnx("scanning addr (7 bit): %0x", i); - g_dev = new MEASAirspeed(bus, i); - if (OK == g_dev->Airspeed::init()) { - warnx("SUCCESS!"); - exit(0); - } else { - delete g_dev; - } - - } + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) goto fail; /* try the MS5525DSO next if init fails */ - if (OK != g_dev->Airspeed::init()) + if (OK != g_dev->Airspeed::init()) { delete g_dev; g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); - /* check if the MS5525DSO was instantiated */ - if (g_dev == nullptr) - goto fail; + /* check if the MS5525DSO was instantiated */ + if (g_dev == nullptr) + goto fail; - /* both versions failed if the init for the MS5525DSO fails, give up */ - if (OK != g_dev->Airspeed::init()) - goto fail; + /* both versions failed if the init for the MS5525DSO fails, give up */ + if (OK != g_dev->Airspeed::init()) + goto fail; + } /* set the poll rate to default, starts automatic data collection */ fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); -- cgit v1.2.3 From 830dff9b6a6fc7c53a0974b80b2d2582bda2df0a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 25 Jul 2013 11:16:25 +0200 Subject: First operational test version, provides correct readings (as far as tests were possible) --- src/drivers/meas_airspeed/meas_airspeed.cpp | 40 ++++++++++++++--------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 5dcc97e6f..7a2e22c01 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -91,18 +91,10 @@ #define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ /* Register address */ -#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ -#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */ -#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */ -#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */ -#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ -#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */ - -/** - * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. - * You can set this value to 12 if you want a zero reading below 15km/h. - */ -#define MIN_ACCURATE_DIFF_PRES_PA 0 +#define ADDR_READ_MR 0x00 /* write to this address to start conversion */ +#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */ +#define ADDR_READ_DF3 0x01 +#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ @@ -143,7 +135,7 @@ MEASAirspeed::measure() /* * Send the command to begin a measurement. */ - uint8_t cmd = ADDR_RESET_CMD; + uint8_t cmd = 0; ret = transfer(&cmd, 1, nullptr, 0); if (OK != ret) { @@ -163,7 +155,8 @@ MEASAirspeed::collect() int ret = -EIO; /* read from the sensor */ - uint8_t val[2] = {0, 0}; + uint8_t val[4] = {0, 0, 0, 0}; + perf_begin(_sample_perf); @@ -174,18 +167,24 @@ MEASAirspeed::collect() return ret; } - uint16_t diff_pres_pa = val[1] << 8 | val[0]; + uint8_t status = val[0] & 0xC0; - if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - diff_pres_pa = 0; - - } else { - diff_pres_pa -= _diff_pres_offset; + if (status == 2) { + log("err: stale data"); + } else if (status == 3) { + log("err: fault"); } + uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); + uint16_t temp = (val[3] & 0xE0) << 8 | val[2]; + + diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); + diff_pres_pa -= _diff_pres_offset; + // XXX we may want to smooth out the readings to remove noise. _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].temperature = temp; _reports[_next_report].differential_pressure_pa = diff_pres_pa; // Track maximum differential pressure measured (so we can work out top speed). @@ -403,6 +402,7 @@ test() warnx("periodic read %u", i); warnx("diff pressure: %d pa", report.differential_pressure_pa); + warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature); } errx(0, "PASS"); -- cgit v1.2.3 From 382c637fab66291a28b18f7481aad3b866de6639 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 15:41:10 +0200 Subject: Fixed stack sizes for airspeed drivers --- src/drivers/ets_airspeed/module.mk | 2 +- src/drivers/meas_airspeed/module.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk index cb5d3b1ed..15346c5c5 100644 --- a/src/drivers/ets_airspeed/module.mk +++ b/src/drivers/ets_airspeed/module.mk @@ -36,6 +36,6 @@ # MODULE_COMMAND = ets_airspeed -MODULE_STACKSIZE = 1024 +MODULE_STACKSIZE = 2048 SRCS = ets_airspeed.cpp diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk index ddcd54351..fed4078b6 100644 --- a/src/drivers/meas_airspeed/module.mk +++ b/src/drivers/meas_airspeed/module.mk @@ -36,6 +36,6 @@ # MODULE_COMMAND = meas_airspeed -MODULE_STACKSIZE = 1024 +MODULE_STACKSIZE = 2048 SRCS = meas_airspeed.cpp -- cgit v1.2.3 From f4e115160766510ef135bc02449e08fd26b87cf1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 15:43:31 +0200 Subject: Hotfix: Cleaned up outdated docs --- Documentation/commander_app.odg | Bin 11628 -> 0 bytes Documentation/commander_app.png | Bin 25356 -> 0 bytes Documentation/position_control.odg | Bin 12559 -> 0 bytes Documentation/position_control.png | Bin 36561 -> 0 bytes Documentation/position_estimator_app.odg | Bin 12160 -> 0 bytes Documentation/position_estimator_app.pdf | Bin 14243 -> 0 bytes Documentation/position_estimator_app.png | Bin 29623 -> 0 bytes Documentation/state_machine.odg | Bin 18576 -> 0 bytes Documentation/state_machine.png | Bin 208880 -> 0 bytes 9 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 Documentation/commander_app.odg delete mode 100644 Documentation/commander_app.png delete mode 100644 Documentation/position_control.odg delete mode 100644 Documentation/position_control.png delete mode 100644 Documentation/position_estimator_app.odg delete mode 100644 Documentation/position_estimator_app.pdf delete mode 100644 Documentation/position_estimator_app.png delete mode 100644 Documentation/state_machine.odg delete mode 100644 Documentation/state_machine.png diff --git a/Documentation/commander_app.odg b/Documentation/commander_app.odg deleted file mode 100644 index 17459f7cf..000000000 Binary files a/Documentation/commander_app.odg and /dev/null differ diff --git a/Documentation/commander_app.png b/Documentation/commander_app.png deleted file mode 100644 index 6503817da..000000000 Binary files a/Documentation/commander_app.png and /dev/null differ diff --git a/Documentation/position_control.odg b/Documentation/position_control.odg deleted file mode 100644 index 5fb002c5e..000000000 Binary files a/Documentation/position_control.odg and /dev/null differ diff --git a/Documentation/position_control.png b/Documentation/position_control.png deleted file mode 100644 index d8d1a8b0c..000000000 Binary files a/Documentation/position_control.png and /dev/null differ diff --git a/Documentation/position_estimator_app.odg b/Documentation/position_estimator_app.odg deleted file mode 100644 index a6fc67373..000000000 Binary files a/Documentation/position_estimator_app.odg and /dev/null differ diff --git a/Documentation/position_estimator_app.pdf b/Documentation/position_estimator_app.pdf deleted file mode 100644 index bc07209ee..000000000 Binary files a/Documentation/position_estimator_app.pdf and /dev/null differ diff --git a/Documentation/position_estimator_app.png b/Documentation/position_estimator_app.png deleted file mode 100644 index 377549f63..000000000 Binary files a/Documentation/position_estimator_app.png and /dev/null differ diff --git a/Documentation/state_machine.odg b/Documentation/state_machine.odg deleted file mode 100644 index 2f55a13dd..000000000 Binary files a/Documentation/state_machine.odg and /dev/null differ diff --git a/Documentation/state_machine.png b/Documentation/state_machine.png deleted file mode 100644 index 4daeddfc9..000000000 Binary files a/Documentation/state_machine.png and /dev/null differ -- cgit v1.2.3