aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/airspeed/airspeed.cpp394
-rw-r--r--src/drivers/airspeed/airspeed.h176
-rw-r--r--src/drivers/airspeed/module.mk38
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c10
-rw-r--r--src/drivers/ardrone_interface/ardrone_motor_control.c115
-rw-r--r--src/drivers/blinkm/blinkm.cpp107
-rw-r--r--src/drivers/bma180/bma180.cpp141
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h (renamed from src/drivers/boards/px4fmu/px4fmu_internal.h)98
-rw-r--r--src/drivers/boards/px4fmu-v1/module.mk (renamed from src/drivers/boards/px4fmu/module.mk)0
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_can.c (renamed from src/drivers/boards/px4fmu/px4fmu_can.c)2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_init.c (renamed from src/drivers/boards/px4fmu/px4fmu_init.c)21
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_led.c (renamed from src/drivers/boards/px4fmu/px4fmu_led.c)21
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c (renamed from src/drivers/boards/px4fmu/px4fmu_pwm_servo.c)10
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_spi.c (renamed from src/drivers/boards/px4fmu/px4fmu_spi.c)2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_usb.c (renamed from src/drivers/boards/px4fmu/px4fmu_usb.c)2
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h214
-rw-r--r--src/drivers/boards/px4fmu-v2/module.mk10
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c332
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_led.c97
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_can.c144
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c105
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c159
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_usb.c108
-rw-r--r--src/drivers/boards/px4io-v1/board_config.h (renamed from src/drivers/boards/px4io/px4io_internal.h)20
-rw-r--r--src/drivers/boards/px4io-v1/module.mk (renamed from src/drivers/boards/px4io/module.mk)0
-rw-r--r--src/drivers/boards/px4io-v1/px4io_init.c (renamed from src/drivers/boards/px4io/px4io_init.c)2
-rw-r--r--src/drivers/boards/px4io-v1/px4io_pwm_servo.c (renamed from src/drivers/boards/px4io/px4io_pwm_servo.c)0
-rw-r--r--src/drivers/boards/px4io-v2/board_config.h138
-rw-r--r--src/drivers/boards/px4io-v2/module.mk6
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_init.c158
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c123
-rw-r--r--src/drivers/device/cdev.cpp64
-rw-r--r--src/drivers/device/device.cpp21
-rw-r--r--src/drivers/device/device.h96
-rw-r--r--src/drivers/device/i2c.h14
-rw-r--r--src/drivers/device/ringbuffer.h509
-rw-r--r--src/drivers/device/spi.cpp40
-rw-r--r--src/drivers/device/spi.h24
-rw-r--r--src/drivers/drv_accel.h7
-rw-r--r--src/drivers/drv_airspeed.h14
-rw-r--r--src/drivers/drv_baro.h5
-rw-r--r--src/drivers/drv_device.h62
-rw-r--r--src/drivers/drv_gpio.h63
-rw-r--r--src/drivers/drv_gps.h7
-rw-r--r--src/drivers/drv_gyro.h5
-rw-r--r--src/drivers/drv_hrt.h14
-rw-r--r--src/drivers/drv_led.h3
-rw-r--r--src/drivers/drv_mag.h27
-rw-r--r--src/drivers/drv_pwm_output.h102
-rw-r--r--src/drivers/drv_range_finder.h1
-rw-r--r--src/drivers/drv_rc_input.h60
-rw-r--r--src/drivers/drv_rgbled.h128
-rw-r--r--src/drivers/drv_sbus.h58
-rw-r--r--src/drivers/drv_sensor.h4
-rw-r--r--src/drivers/drv_tone_alarm.h27
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp510
-rw-r--r--src/drivers/ets_airspeed/module.mk2
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.c289
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.h51
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c266
-rw-r--r--src/drivers/frsky_telemetry/module.mk41
-rw-r--r--src/drivers/gps/gps.cpp211
-rw-r--r--src/drivers/gps/gps_helper.cpp14
-rw-r--r--src/drivers/gps/gps_helper.h8
-rw-r--r--src/drivers/gps/module.mk2
-rw-r--r--src/drivers/gps/mtk.cpp37
-rw-r--r--src/drivers/gps/mtk.h11
-rw-r--r--src/drivers/gps/ubx.cpp887
-rw-r--r--src/drivers/gps/ubx.h82
-rw-r--r--src/drivers/hil/hil.cpp14
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp442
-rw-r--r--src/drivers/hott/comms.cpp92
-rw-r--r--src/drivers/hott/comms.h46
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp238
-rw-r--r--src/drivers/hott/hott_sensors/module.mk42
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp (renamed from src/drivers/hott_telemetry/hott_telemetry_main.c)190
-rw-r--r--src/drivers/hott/hott_telemetry/module.mk (renamed from src/drivers/hott_telemetry/module.mk)7
-rw-r--r--src/drivers/hott/messages.cpp330
-rw-r--r--src/drivers/hott/messages.h249
-rw-r--r--src/drivers/hott_telemetry/messages.c99
-rw-r--r--src/drivers/hott_telemetry/messages.h124
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp468
-rw-r--r--src/drivers/led/led.cpp12
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp2036
-rw-r--r--src/drivers/lsm303d/module.mk8
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp107
-rw-r--r--src/drivers/md25/BlockSysIdent.cpp8
-rw-r--r--src/drivers/md25/BlockSysIdent.hpp10
-rw-r--r--src/drivers/md25/md25.cpp87
-rw-r--r--src/drivers/md25/md25.hpp18
-rw-r--r--src/drivers/md25/md25_main.cpp49
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp520
-rw-r--r--src/drivers/meas_airspeed/module.mk41
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp618
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp660
-rw-r--r--src/drivers/ms5611/module.mk2
-rw-r--r--src/drivers/ms5611/ms5611.cpp572
-rw-r--r--src/drivers/ms5611/ms5611.h85
-rw-r--r--src/drivers/ms5611/ms5611_i2c.cpp278
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp276
-rw-r--r--src/drivers/px4fmu/fmu.cpp895
-rw-r--r--src/drivers/px4io/module.mk7
-rw-r--r--src/drivers/px4io/px4io.cpp2474
-rw-r--r--src/drivers/px4io/px4io_i2c.cpp169
-rw-r--r--src/drivers/px4io/px4io_serial.cpp679
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp (renamed from src/drivers/px4io/uploader.cpp)148
-rw-r--r--src/drivers/px4io/uploader.h4
-rw-r--r--src/drivers/rgbled/module.mk6
-rw-r--r--src/drivers/rgbled/rgbled.cpp713
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp328
-rw-r--r--src/drivers/roboclaw/RoboClaw.hpp192
-rw-r--r--src/drivers/roboclaw/module.mk41
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp195
-rw-r--r--src/drivers/stm32/adc/adc.cpp14
-rw-r--r--src/drivers/stm32/drv_hrt.c188
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c6
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp284
117 files changed, 16545 insertions, 4045 deletions
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
new file mode 100644
index 000000000..771f2128f
--- /dev/null
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -0,0 +1,394 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 <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 <arch/board/board.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <drivers/airspeed/airspeed.h>
+
+Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
+ I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000),
+ _reports(nullptr),
+ _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
+ _max_differential_pressure_pa(0),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _diff_pres_offset(0.0f),
+ _airspeed_pub(-1),
+ _class_instance(-1),
+ _conversion_interval(conversion_interval),
+ _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
+{
+ // enable debug() calls
+ _debug_enabled = false;
+
+ // 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();
+
+ if (_class_instance != -1)
+ unregister_class_devname(AIRSPEED_DEVICE_PATH, _class_instance);
+
+ /* free any existing reports */
+ if (_reports != nullptr)
+ delete _reports;
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
+}
+
+int
+Airspeed::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(differential_pressure_s));
+ if (_reports == nullptr)
+ goto out;
+
+ /* register alternate interfaces if we have to */
+ _class_instance = register_class_devname(AIRSPEED_DEVICE_PATH);
+
+ /* publication init */
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct differential_pressure_s arp;
+ measure();
+ _reports->get(&arp);
+
+ /* measurement will have generated a report, publish */
+ _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp);
+
+ if (_airspeed_pub < 0)
+ warnx("failed to create airspeed sensor object. uORB started?");
+ }
+
+ 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()
+{
+ /* on initial power up the device needs more than one retry
+ for detection. Once it is running then retries aren't
+ needed
+ */
+ _retries = 4;
+ int ret = measure();
+ _retries = 2;
+ return ret;
+}
+
+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: {
+ /* 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 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(differential_pressure_s);
+ differential_pressure_s *abuf = reinterpret_cast<differential_pressure_s *>(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(abuf)) {
+ ret += sizeof(*abuf);
+ abuf++;
+ }
+ }
+
+ /* 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(_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(abuf)) {
+ ret = sizeof(*abuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+void
+Airspeed::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)&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);
+ _reports->print_info("report queue");
+}
+
+void
+Airspeed::new_report(const differential_pressure_s &report)
+{
+ if (!_reports->force(&report))
+ perf_count(_buffer_overflows);
+}
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
new file mode 100644
index 000000000..c27b1bcd8
--- /dev/null
+++ b/src/drivers/airspeed/airspeed.h
@@ -0,0 +1,176 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 <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 <arch/board/board.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+/* 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 __EXPORT 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.
+ */
+ virtual void print_info();
+
+private:
+ RingBuffer *_reports;
+ perf_counter_t _buffer_overflows;
+
+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;
+ float _max_differential_pressure_pa;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ float _diff_pres_offset;
+
+ orb_advert_t _airspeed_pub;
+
+ int _class_instance;
+
+ unsigned _conversion_interval;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+
+
+ /**
+ * 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);
+
+ /**
+ * add a new report to the reports queue
+ *
+ * @param report differential_pressure_s report
+ */
+ void new_report(const differential_pressure_s &report);
+};
+
+
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/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 735bdb41a..b88f61ce8 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -53,8 +53,10 @@
#include <sys/prctl.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/safety.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <systemlib/systemlib.h>
@@ -243,16 +245,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
int led_counter = 0;
/* declare and safely initialize all structs */
- struct vehicle_status_s state;
- memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
memset(&actuator_controls, 0, sizeof(actuator_controls));
struct actuator_armed_s armed;
+ //XXX is this necessairy?
armed.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
printf("[ardrone_interface] Motors initialized - ready.\n");
@@ -322,8 +322,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
} else {
/* MAIN OPERATION MODE */
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of the actuator controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c
index ecd31a073..81f634992 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.c
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.c
@@ -41,11 +41,11 @@
#include <stdio.h>
#include <fcntl.h>
#include <unistd.h>
+#include <math.h>
#include <drivers/drv_gpio.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/actuator_outputs.h>
-#include <uORB/topics/actuator_controls_effective.h>
#include <systemlib/err.h>
#include "ardrone_motor_control.h"
@@ -109,7 +109,7 @@ int ar_multiplexing_init()
{
int fd;
- fd = open(GPIO_DEVICE_PATH, 0);
+ fd = open(PX4FMU_DEVICE_PATH, 0);
if (fd < 0) {
warn("GPIO: open fail");
@@ -369,11 +369,9 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float yaw_control = actuators->control[2];
float motor_thrust = actuators->control[3];
- //printf("AMO: Roll: %4.4f, Pitch: %4.4f, Yaw: %4.4f, Thrust: %4.4f\n",roll_control, pitch_control, yaw_control, motor_thrust);
-
const float min_thrust = 0.02f; /**< 2% minimum thrust */
const float max_thrust = 1.0f; /**< 100% max thrust */
- const float scaling = 500.0f; /**< 100% thrust equals a value of 500 which works, 512 leads to cutoff */
+ const float scaling = 510.0f; /**< 100% thrust equals a value of 510 which works, 512 leads to cutoff */
const float min_gas = min_thrust * scaling; /**< value range sent to motors, minimum */
const float max_gas = max_thrust * scaling; /**< value range sent to motors, maximum */
@@ -382,110 +380,77 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float motor_calc[4] = {0};
float output_band = 0.0f;
- float band_factor = 0.75f;
const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */
- float yaw_factor = 1.0f;
static bool initialized = false;
- /* publish effective outputs */
- static struct actuator_controls_effective_s actuator_controls_effective;
- static orb_advert_t actuator_controls_effective_pub;
-
- if (motor_thrust <= min_thrust) {
- motor_thrust = min_thrust;
- output_band = 0.0f;
- } else if (motor_thrust < startpoint_full_control && motor_thrust > min_thrust) {
- output_band = band_factor * (motor_thrust - min_thrust);
- } else if (motor_thrust >= startpoint_full_control && motor_thrust < max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * startpoint_full_control;
- } else if (motor_thrust >= max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * (max_thrust - motor_thrust);
+
+ /* linearly scale the control inputs from 0 to startpoint_full_control */
+ if (motor_thrust < startpoint_full_control) {
+ output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1
+ } else {
+ output_band = 1.0f;
}
+ roll_control *= output_band;
+ pitch_control *= output_band;
+ yaw_control *= output_band;
+
+
//add the yaw, nick and roll components to the basic thrust //TODO:this should be done by the mixer
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
- // if we are not in the output band
- if (!(motor_calc[0] < motor_thrust + output_band && motor_calc[0] > motor_thrust - output_band
- && motor_calc[1] < motor_thrust + output_band && motor_calc[1] > motor_thrust - output_band
- && motor_calc[2] < motor_thrust + output_band && motor_calc[2] > motor_thrust - output_band
- && motor_calc[3] < motor_thrust + output_band && motor_calc[3] > motor_thrust - output_band)) {
+ /* if one motor is saturated, reduce throttle */
+ float saturation = fmaxf(fmaxf(motor_calc[0], motor_calc[1]),fmaxf(motor_calc[2], motor_calc[3])) - max_thrust;
+
+
+ if (saturation > 0.0f) {
+
+ /* reduce the motor thrust according to the saturation */
+ motor_thrust = motor_thrust - saturation;
- yaw_factor = 0.5f;
- yaw_control *= yaw_factor;
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
}
- for (int i = 0; i < 4; i++) {
- //check for limits
- if (motor_calc[i] < motor_thrust - output_band) {
- motor_calc[i] = motor_thrust - output_band;
- }
-
- if (motor_calc[i] > motor_thrust + output_band) {
- motor_calc[i] = motor_thrust + output_band;
- }
- }
-
- /* publish effective outputs */
- actuator_controls_effective.control_effective[0] = roll_control;
- actuator_controls_effective.control_effective[1] = pitch_control;
- /* yaw output after limiting */
- actuator_controls_effective.control_effective[2] = yaw_control;
- /* possible motor thrust limiting */
- actuator_controls_effective.control_effective[3] = (motor_calc[0] + motor_calc[1] + motor_calc[2] + motor_calc[3]) / 4.0f;
-
- if (!initialized) {
- /* advertise and publish */
- actuator_controls_effective_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, &actuator_controls_effective);
- initialized = true;
- } else {
- /* already initialized, just publishing */
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, actuator_controls_effective_pub, &actuator_controls_effective);
- }
-
/* set the motor values */
- /* scale up from 0..1 to 10..512) */
+ /* scale up from 0..1 to 10..500) */
motor_pwm[0] = (uint16_t) (motor_calc[0] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[1] = (uint16_t) (motor_calc[1] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[2] = (uint16_t) (motor_calc[2] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[3] = (uint16_t) (motor_calc[3] * ((float)max_gas - min_gas) + min_gas);
- /* Keep motors spinning while armed and prevent overflows */
-
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : 10;
- motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : 10;
- motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : 10;
- motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : 10;
-
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] <= 511) ? motor_pwm[0] : 511;
- motor_pwm[1] = (motor_pwm[1] <= 511) ? motor_pwm[1] : 511;
- motor_pwm[2] = (motor_pwm[2] <= 511) ? motor_pwm[2] : 511;
- motor_pwm[3] = (motor_pwm[3] <= 511) ? motor_pwm[3] : 511;
+ /* scale up from 0..1 to 10..500) */
+ motor_pwm[0] = (uint16_t) (motor_calc[0] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[1] = (uint16_t) (motor_calc[1] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[2] = (uint16_t) (motor_calc[2] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[3] = (uint16_t) (motor_calc[3] * (float)((max_gas - min_gas) + min_gas));
+
+ /* Failsafe logic for min values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : min_gas;
+ motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : min_gas;
+ motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : min_gas;
+ motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : min_gas;
+
+ /* Failsafe logic for max values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] <= max_gas) ? motor_pwm[0] : max_gas;
+ motor_pwm[1] = (motor_pwm[1] <= max_gas) ? motor_pwm[1] : max_gas;
+ motor_pwm[2] = (motor_pwm[2] <= max_gas) ? motor_pwm[2] : max_gas;
+ motor_pwm[3] = (motor_pwm[3] <= max_gas) ? motor_pwm[3] : max_gas;
/* send motors via UART */
ardrone_write_motor_commands(ardrone_write, motor_pwm[0], motor_pwm[1], motor_pwm[2], motor_pwm[3]);
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 3fabfd9a5..2361f4dd1 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -92,9 +92,6 @@
#include <nuttx/config.h>
-#include <arch/board/board.h>
-#include <drivers/device/i2c.h>
-
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
@@ -104,18 +101,23 @@
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
-
-#include <drivers/drv_blinkm.h>
+#include <poll.h>
#include <nuttx/wqueue.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
-
#include <systemlib/systemlib.h>
-#include <poll.h>
+
+#include <board_config.h>
+
+#include <drivers/device/i2c.h>
+#include <drivers/drv_blinkm.h>
+
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_gps_position.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
@@ -375,7 +377,9 @@ BlinkM::led()
{
static int vehicle_status_sub_fd;
+ static int vehicle_control_mode_sub_fd;
static int vehicle_gps_position_sub_fd;
+ static int actuator_armed_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -386,6 +390,8 @@ BlinkM::led()
static int led_interval = 1000;
static int no_data_vehicle_status = 0;
+ static int no_data_vehicle_control_mode = 0;
+ static int no_data_actuator_armed = 0;
static int no_data_vehicle_gps_position = 0;
static bool topic_initialized = false;
@@ -398,6 +404,12 @@ BlinkM::led()
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 1000);
+ vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
+ orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+
+ actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(actuator_armed_sub_fd, 1000);
+
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
@@ -452,12 +464,16 @@ BlinkM::led()
if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
+ struct vehicle_control_mode_s vehicle_control_mode;
+ struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
bool new_data_vehicle_status;
+ bool new_data_vehicle_control_mode;
+ bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -471,6 +487,28 @@ BlinkM::led()
no_data_vehicle_status = 3;
}
+ orb_check(vehicle_control_mode_sub_fd, &new_data_vehicle_control_mode);
+
+ if (new_data_vehicle_control_mode) {
+ orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sub_fd, &vehicle_control_mode);
+ no_data_vehicle_control_mode = 0;
+ } else {
+ no_data_vehicle_control_mode++;
+ if(no_data_vehicle_control_mode >= 3)
+ no_data_vehicle_control_mode = 3;
+ }
+
+ orb_check(actuator_armed_sub_fd, &new_data_actuator_armed);
+
+ if (new_data_actuator_armed) {
+ orb_copy(ORB_ID(actuator_armed), actuator_armed_sub_fd, &actuator_armed);
+ no_data_actuator_armed = 0;
+ } else {
+ no_data_actuator_armed++;
+ if(no_data_actuator_armed >= 3)
+ no_data_actuator_armed = 3;
+ }
+
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
if (new_data_vehicle_gps_position) {
@@ -486,24 +524,24 @@ BlinkM::led()
/* get number of used satellites in navigation */
num_of_used_sats = 0;
- //for(int satloop=0; satloop<20; satloop++) {
- for(int satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
+
+ for(unsigned satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
num_of_used_sats++;
}
}
- if(new_data_vehicle_status || no_data_vehicle_status < 3){
- if(num_of_cells == 0) {
+ if (new_data_vehicle_status || no_data_vehicle_status < 3) {
+ if (num_of_cells == 0) {
/* looking for lipo cells that are connected */
printf("<blinkm> checking cells\n");
for(num_of_cells = 2; num_of_cells < 7; num_of_cells++) {
- if(vehicle_status_raw.voltage_battery < num_of_cells * MAX_CELL_VOLTAGE) break;
+ if(vehicle_status_raw.battery_voltage < num_of_cells * MAX_CELL_VOLTAGE) break;
}
printf("<blinkm> cells found:%d\n", num_of_cells);
} else {
- if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
+ if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
/* LED Pattern for battery low warning */
led_color_1 = LED_YELLOW;
led_color_2 = LED_YELLOW;
@@ -515,7 +553,7 @@ BlinkM::led()
led_color_8 = LED_YELLOW;
led_blink = LED_BLINK;
- } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
+ } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* LED Pattern for battery critical alerting */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -530,7 +568,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_system_armed == false) {
+ if(actuator_armed.armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -554,27 +592,24 @@ BlinkM::led()
led_color_8 = LED_OFF;
led_blink = LED_BLINK;
- /* handle 4th led - flightmode indicator */
- switch((int)vehicle_status_raw.flight_mode) {
- case VEHICLE_FLIGHT_MODE_MANUAL:
- led_color_4 = LED_AMBER;
- break;
-
- case VEHICLE_FLIGHT_MODE_STAB:
- led_color_4 = LED_YELLOW;
- break;
-
- case VEHICLE_FLIGHT_MODE_HOLD:
- led_color_4 = LED_BLUE;
- break;
+ if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
- case VEHICLE_FLIGHT_MODE_AUTO:
+ //XXX please check
+ if (vehicle_control_mode.flag_control_position_enabled)
led_color_4 = LED_GREEN;
- break;
+ else if (vehicle_control_mode.flag_control_velocity_enabled)
+ led_color_4 = LED_BLUE;
+ else if (vehicle_control_mode.flag_control_attitude_enabled)
+ led_color_4 = LED_YELLOW;
+ else if (vehicle_control_mode.flag_control_manual_enabled)
+ led_color_4 = LED_AMBER;
+ else
+ led_color_4 = LED_OFF;
+
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat´s */
+ /* handling used sat�s */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -831,11 +866,13 @@ BlinkM::get_firmware_version(uint8_t version[2])
return transfer(&msg, sizeof(msg), version, 2);
}
+void blinkm_usage();
+
void blinkm_usage() {
- fprintf(stderr, "missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}\n");
- fprintf(stderr, "options:\n");
- fprintf(stderr, "\t-b --bus i2cbus (3)\n");
- fprintf(stderr, "\t-a --blinkmaddr blinkmaddr (9)\n");
+ warnx("missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}");
+ warnx("options:");
+ warnx("\t-b --bus i2cbus (3)");
+ warnx("\t-a --blinkmaddr blinkmaddr (9)");
}
int
diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp
index 4409a8a9c..e43a34805 100644
--- a/src/drivers/bma180/bma180.cpp
+++ b/src/drivers/bma180/bma180.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -59,10 +59,11 @@
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
+#include <drivers/device/ringbuffer.h>
/* oddly, ERROR is not defined for c++ */
@@ -146,15 +147,13 @@ private:
struct hrt_call _call;
unsigned _call_interval;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- struct accel_report *_reports;
+ RingBuffer *_reports;
struct accel_scale _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
+ int _class_instance;
unsigned _current_lowpass;
unsigned _current_range;
@@ -233,20 +232,14 @@ private:
int set_lowpass(unsigned frequency);
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
-
BMA180::BMA180(int bus, spi_dev_e device) :
SPI("BMA180", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 8000000),
_call_interval(0),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
+ _class_instance(-1),
_current_lowpass(0),
_current_range(0),
_sample_perf(perf_alloc(PC_ELAPSED, "bma180_read"))
@@ -270,7 +263,7 @@ BMA180::~BMA180()
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
/* delete the perf counter */
perf_free(_sample_perf);
@@ -286,17 +279,11 @@ BMA180::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _oldest_report = _next_report = 0;
- _reports = new struct accel_report[_num_reports];
+ _reports = new RingBuffer(2, sizeof(accel_report));
if (_reports == nullptr)
goto out;
- /* advertise sensor topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_reports[0]);
-
/* perform soft reset (p48) */
write_reg(ADDR_RESET, SOFT_RESET);
@@ -332,6 +319,19 @@ BMA180::init()
ret = ERROR;
}
+ _class_instance = register_class_devname(ACCEL_DEVICE_PATH);
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ measure();
+
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ struct accel_report arp;
+ _reports->get(&arp);
+
+ /* measurement will have generated a report, publish */
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+ }
+
out:
return ret;
}
@@ -352,6 +352,7 @@ ssize_t
BMA180::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct accel_report);
+ struct accel_report *arp = reinterpret_cast<struct accel_report *>(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -367,10 +368,9 @@ BMA180::read(struct file *filp, char *buffer, size_t buflen)
* we are careful to avoid racing with it.
*/
while (count--) {
- if (_oldest_report != _next_report) {
- memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
- ret += sizeof(_reports[0]);
- INCREMENT(_oldest_report, _num_reports);
+ if (_reports->get(arp)) {
+ ret += sizeof(*arp);
+ arp++;
}
}
@@ -379,12 +379,12 @@ BMA180::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement */
- _oldest_report = _next_report = 0;
+ _reports->flush();
measure();
/* measurement will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(arp))
+ ret = sizeof(*arp);
return ret;
}
@@ -449,31 +449,22 @@ BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
case SENSORIOCSQUEUEDEPTH: {
- /* account for 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 accel_report *buf = new struct accel_report[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;
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
}
+ irqrestore(flags);
+
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
/* XXX implement */
@@ -654,7 +645,7 @@ BMA180::start()
stop();
/* reset the report ring */
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&BMA180::measure_trampoline, this);
@@ -688,7 +679,7 @@ BMA180::measure()
// } raw_report;
// #pragma pack(pop)
- accel_report *report = &_reports[_next_report];
+ struct accel_report report;
/* start the performance counter */
perf_begin(_sample_perf);
@@ -708,45 +699,42 @@ BMA180::measure()
* them before. There is no good way to synchronise with the internal
* measurement flow without using the external interrupt.
*/
- _reports[_next_report].timestamp = hrt_absolute_time();
+ report.timestamp = hrt_absolute_time();
+ report.error_count = 0;
/*
* y of board is x of sensor and x of board is -y of sensor
* perform only the axis assignment here.
* Two non-value bits are discarded directly
*/
- report->y_raw = read_reg(ADDR_ACC_X_LSB + 0);
- report->y_raw |= read_reg(ADDR_ACC_X_LSB + 1) << 8;
- report->x_raw = read_reg(ADDR_ACC_X_LSB + 2);
- report->x_raw |= read_reg(ADDR_ACC_X_LSB + 3) << 8;
- report->z_raw = read_reg(ADDR_ACC_X_LSB + 4);
- report->z_raw |= read_reg(ADDR_ACC_X_LSB + 5) << 8;
+ report.y_raw = read_reg(ADDR_ACC_X_LSB + 0);
+ report.y_raw |= read_reg(ADDR_ACC_X_LSB + 1) << 8;
+ report.x_raw = read_reg(ADDR_ACC_X_LSB + 2);
+ report.x_raw |= read_reg(ADDR_ACC_X_LSB + 3) << 8;
+ report.z_raw = read_reg(ADDR_ACC_X_LSB + 4);
+ report.z_raw |= read_reg(ADDR_ACC_X_LSB + 5) << 8;
/* discard two non-value bits in the 16 bit measurement */
- report->x_raw = (report->x_raw / 4);
- report->y_raw = (report->y_raw / 4);
- report->z_raw = (report->z_raw / 4);
+ report.x_raw = (report.x_raw / 4);
+ report.y_raw = (report.y_raw / 4);
+ report.z_raw = (report.z_raw / 4);
/* invert y axis, due to 14 bit data no overflow can occur in the negation */
- report->y_raw = -report->y_raw;
-
- report->x = ((report->x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- report->y = ((report->y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- report->z = ((report->z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
- report->scaling = _accel_range_scale;
- report->range_m_s2 = _accel_range_m_s2;
+ report.y_raw = -report.y_raw;
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
+ report.x = ((report.x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ report.y = ((report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ report.z = ((report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+ report.scaling = _accel_range_scale;
+ report.range_m_s2 = _accel_range_m_s2;
- /* if we are running up against the oldest report, fix it */
- if (_next_report == _oldest_report)
- INCREMENT(_oldest_report, _num_reports);
+ _reports->force(&report);
/* notify anyone waiting for data */
poll_notify(POLLIN);
/* publish for subscribers */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, report);
+ if (_accel_topic > 0 && !(_pub_blocked))
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, &report);
/* stop the perf counter */
perf_end(_sample_perf);
@@ -756,8 +744,7 @@ void
BMA180::print_info()
{
perf_print_counter(_sample_perf);
- printf("report queue: %u (%u/%u @ %p)\n",
- _num_reports, _oldest_report, _next_report, _reports);
+ _reports->print_info("report queue");
}
/**
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 383a046ff..02c26b5c0 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -32,9 +32,9 @@
****************************************************************************/
/**
- * @file px4fmu_internal.h
+ * @file board_config.h
*
- * PX4FMU internal definitions
+ * PX4FMUv1 internal definitions
*/
#pragma once
@@ -51,13 +51,17 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include <stm32.h>
-
+#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS2"
+#define UDID_START 0x1FFF7A10
+
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"
//#endif
@@ -74,15 +78,47 @@ __BEGIN_DECLS
/* External interrupts */
#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
-// XXX MPU6000 DRDY?
/* SPI chip selects */
-
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+/*
+ * Use these in place of the spi_dev_e enumeration to
+ * select a specific SPI device on SPI1
+ */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL 2
+#define PX4_SPIDEV_MPU 3
+
+/*
+ * Optional devices on IO's external port
+ */
+#define PX4_SPIDEV_ACCEL_MAG 2
+
+/*
+ * I2C busses
+ */
+#define PX4_I2C_BUS_ESC 1
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_EXPANSION 3
+#define PX4_I2C_BUS_LED 3
+
+/*
+ * Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+#define PX4_I2C_OBDEV_MS5611 0x76
+#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
+#define PX4_I2C_OBDEV_LED 0x55
+
+#define PX4_I2C_OBDEV_PX4IO_BL 0x18
+#define PX4_I2C_OBDEV_PX4IO 0x1a
+
/* User GPIOs
*
* GPIO0-1 are the buffered high-power GPIOs.
@@ -107,31 +143,45 @@ __BEGIN_DECLS
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+/*
+ * Tone alarm output
+ */
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
+
+/*
+ * PWM
+ *
+ * Four PWM outputs can be configured on pins otherwise shared with
+ * USART2; two can take the flow control pins if they are not being used.
+ *
+ * Pins:
+ *
+ * CTS - PA0 - TIM2CH1
+ * RTS - PA1 - TIM2CH2
+ * TX - PA2 - TIM2CH3
+ * RX - PA3 - TIM2CH4
+ *
+ */
+#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
+#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
+#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
+#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
+
/* USB OTG FS
*
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
*/
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
-/* PWM
- *
- * The PX4FMU has five PWM outputs, of which only the output on
- * pin PC8 is fixed assigned to this function. The other four possible
- * pwm sources are the TX, RX, RTS and CTS pins of USART2
- *
- * Alternate function mapping:
- * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
+/* High-resolution timer
*/
-
-#ifdef CONFIG_PWM
-# if defined(CONFIG_STM32_TIM3_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 3
-# elif defined(CONFIG_STM32_TIM8_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 8
-# endif
-#endif
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
/****************************************************************************************************
* Public Types
diff --git a/src/drivers/boards/px4fmu/module.mk b/src/drivers/boards/px4fmu-v1/module.mk
index 66b776917..66b776917 100644
--- a/src/drivers/boards/px4fmu/module.mk
+++ b/src/drivers/boards/px4fmu-v1/module.mk
diff --git a/src/drivers/boards/px4fmu/px4fmu_can.c b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
index 187689ff9..1e1f10040 100644
--- a/src/drivers/boards/px4fmu/px4fmu_can.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
@@ -54,7 +54,7 @@
#include "stm32.h"
#include "stm32_can.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#ifdef CONFIG_CAN
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
index 212a92cfa..4b12b75f9 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
@@ -59,7 +59,7 @@
#include <nuttx/analog/adc.h>
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
@@ -194,7 +194,7 @@ __EXPORT int nsh_archinitialize(void)
/* initial LED state */
drv_led_start();
led_off(LED_AMBER);
- led_on(LED_BLUE);
+ led_off(LED_BLUE);
/* Configure SPI-based devices */
@@ -222,14 +222,9 @@ __EXPORT int nsh_archinitialize(void)
* If SPI2 is enabled in the defconfig, we loose some ADC pins as chip selects.
* Keep the SPI2 init optional and conditionally initialize the ADC pins
*/
- spi2 = up_spiinitialize(2);
- if (!spi2) {
- message("[boot] Enabling IN12/13 instead of SPI2\n");
- /* no SPI2, use pins for ADC */
- stm32_configgpio(GPIO_ADC1_IN12);
- stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
- } else {
+ #ifdef CONFIG_STM32_SPI2
+ spi2 = up_spiinitialize(2);
/* Default SPI2 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi2, 10000000);
SPI_SETBITS(spi2, 8);
@@ -238,7 +233,13 @@ __EXPORT int nsh_archinitialize(void)
SPI_SELECT(spi2, PX4_SPIDEV_ACCEL_MAG, false);
message("[boot] Initialized SPI port2 (ADC IN12/13 blocked)\n");
- }
+ #else
+ spi2 = NULL;
+ message("[boot] Enabling IN12/13 instead of SPI2\n");
+ /* no SPI2, use pins for ADC */
+ stm32_configgpio(GPIO_ADC1_IN12);
+ stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
+ #endif
/* Get the SPI port for the microSD slot */
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
index 31b25984e..ea91f34ad 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
@@ -42,7 +42,7 @@
#include <stdbool.h>
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include <arch/board/board.h>
@@ -57,6 +57,7 @@ __BEGIN_DECLS
extern void led_init();
extern void led_on(int led);
extern void led_off(int led);
+extern void led_toggle(int led);
__END_DECLS
__EXPORT void led_init()
@@ -94,3 +95,21 @@ __EXPORT void led_off(int led)
stm32_gpiowrite(GPIO_LED2, true);
}
}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 0)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED2))
+ stm32_gpiowrite(GPIO_LED2, false);
+ else
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
index d85131dd8..848e21d79 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
@@ -41,15 +41,15 @@
#include <stdint.h>
-#include <drivers/stm32/drv_pwm_servo.h>
-
-#include <arch/board/board.h>
-#include <drivers/drv_pwm_output.h>
-
#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "board_config.h"
+
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
{
.base = STM32_TIM2_BASE,
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
index e05ddecf3..17e6862f7 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Public Functions
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
index 0be981c1e..0fc8569aa 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
new file mode 100644
index 000000000..7cfca7656
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -0,0 +1,214 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 board_config.h
+ *
+ * PX4FMUv2 internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+#define UDID_START 0x1FFF7A10
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
+#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
+#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
+#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
+#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
+#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
+#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
+#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
+#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
+
+
+/* PX4FMU GPIOs ***********************************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
+
+/* External interrupts */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4)
+#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
+
+/* Data ready pins off */
+#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_MAG_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN4)
+#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
+
+/* SPI1 off */
+#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_SPI1_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN7)
+
+/* SPI1 chip selects off */
+#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN13)
+#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7)
+#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
+
+/* SPI chip selects */
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
+#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
+#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
+
+/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL_MAG 2
+#define PX4_SPIDEV_BARO 3
+#define PX4_SPIDEV_MPU 4
+
+/* I2C busses */
+#define PX4_I2C_BUS_EXPANSION 1
+#define PX4_I2C_BUS_LED 2
+
+/* Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_LED 0x55
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+
+/* User GPIOs
+ *
+ * GPIO0-5 are the PWM servo outputs.
+ */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+
+/* Power supply control and monitoring GPIOs */
+#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
+#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_VDD_SERVO_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7)
+#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_VDD_5V_HIPOWER_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10)
+#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
+
+/* Tone alarm output */
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
+
+/* PWM
+ *
+ * Six PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PE14 : TIM1_CH4
+ * CH2 : PE13 : TIM1_CH3
+ * CH3 : PE11 : TIM1_CH2
+ * CH4 : PE9 : TIM1_CH1
+ * CH5 : PD13 : TIM4_CH2
+ * CH6 : PD14 : TIM4_CH3
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
+#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
+#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2
+
+/* USB OTG FS
+ *
+ * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
+ */
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/module.mk b/src/drivers/boards/px4fmu-v2/module.mk
new file mode 100644
index 000000000..99d37eeca
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/module.mk
@@ -0,0 +1,10 @@
+#
+# Board-specific startup code for the PX4FMUv2
+#
+
+SRCS = px4fmu_can.c \
+ px4fmu2_init.c \
+ px4fmu_pwm_servo.c \
+ px4fmu_spi.c \
+ px4fmu_usb.c \
+ px4fmu2_led.c
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
new file mode 100644
index 000000000..71414d62c
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -0,0 +1,332 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+#include <nuttx/gran.h>
+
+#include <stm32.h>
+#include "board_config.h"
+#include <stm32_uart.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
+
+#include <systemlib/cpuload.h>
+#include <systemlib/perf_counter.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_FAT_DMAMEMORY)
+# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
+# error microSD DMA support requires CONFIG_GRAN
+# endif
+
+static GRAN_HANDLE dma_allocator;
+
+/*
+ * The DMA heap size constrains the total number of things that can be
+ * ready to do DMA at a time.
+ *
+ * For example, FAT DMA depends on one sector-sized buffer per filesystem plus
+ * one sector-sized buffer per file.
+ *
+ * We use a fundamental alignment / granule size of 64B; this is sufficient
+ * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
+ */
+static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
+static perf_counter_t g_dma_perf;
+
+static void
+dma_alloc_init(void)
+{
+ dma_allocator = gran_initialize(g_dma_heap,
+ sizeof(g_dma_heap),
+ 7, /* 128B granule - must be > alignment (XXX bug?) */
+ 6); /* 64B alignment */
+ if (dma_allocator == NULL) {
+ message("[boot] DMA allocator setup FAILED");
+ } else {
+ g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/*
+ * DMA-aware allocator stubs for the FAT filesystem.
+ */
+
+__EXPORT void *fat_dma_alloc(size_t size);
+__EXPORT void fat_dma_free(FAR void *memory, size_t size);
+
+void *
+fat_dma_alloc(size_t size)
+{
+ perf_count(g_dma_perf);
+ return gran_alloc(dma_allocator, size);
+}
+
+void
+fat_dma_free(FAR void *memory, size_t size)
+{
+ gran_free(dma_allocator, memory, size);
+}
+
+#else
+
+# define dma_alloc_init()
+
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void
+stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi1;
+static struct spi_dev_s *spi2;
+static struct sdio_dev_s *sdio;
+
+#include <math.h>
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
+ stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
+ stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
+ // stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
+ // stm32_configgpio(GPIO_ADC1_IN11); /* unused */
+ // stm32_configgpio(GPIO_ADC1_IN12); /* used by MPU6000 CS */
+ stm32_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
+ stm32_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
+ stm32_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
+
+ /* configure power supply control/sense pins */
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
+ stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
+ stm32_configgpio(GPIO_VDD_BRICK_VALID);
+ stm32_configgpio(GPIO_VDD_SERVO_VALID);
+ stm32_configgpio(GPIO_VDD_5V_HIPOWER_OC);
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_OC);
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure SPI-based devices */
+
+ spi1 = up_spiinitialize(1);
+
+ if (!spi1) {
+ message("[boot] FAILED to initialize SPI port 1\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI1 to 1MHz and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi1, 10000000);
+ SPI_SETBITS(spi1, 8);
+ SPI_SETMODE(spi1, SPIDEV_MODE3);
+ SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
+ up_udelay(20);
+
+ message("[boot] Initialized SPI port 1 (SENSORS)\n");
+
+ /* Get the SPI port for the FRAM */
+
+ spi2 = up_spiinitialize(2);
+
+ if (!spi2) {
+ message("[boot] FAILED to initialize SPI port 2\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max)
+ * and de-assert the known chip selects. */
+
+ // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated
+ SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000);
+ SPI_SETBITS(spi2, 8);
+ SPI_SETMODE(spi2, SPIDEV_MODE3);
+ SPI_SELECT(spi2, SPIDEV_FLASH, false);
+
+ message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
+
+ #ifdef CONFIG_MMCSD
+ /* First, get an instance of the SDIO interface */
+
+ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!sdio) {
+ message("[boot] Failed to initialize SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+ int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ if (ret != OK) {
+ message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+
+ /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
+ sdio_mediachange(sdio, true);
+
+ message("[boot] Initialized SDIO\n");
+ #endif
+
+ return OK;
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
new file mode 100644
index 000000000..a856ccb02
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * 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 px4fmu2_led.c
+ *
+ * PX4FMU LED backend.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+__EXPORT void led_init()
+{
+ /* Configure LED1 GPIO for output */
+
+ stm32_configgpio(GPIO_LED1);
+}
+
+__EXPORT void led_on(int led)
+{
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+}
+
+__EXPORT void led_off(int led)
+{
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_can.c b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
new file mode 100644
index 000000000..f66c7cd79
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
@@ -0,0 +1,144 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif \ No newline at end of file
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
new file mode 100644
index 000000000..600dfef41
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include <stdint.h>
+
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
+
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "board_config.h"
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
new file mode 100644
index 000000000..c66c490a7
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -0,0 +1,159 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include <up_arch.h>
+#include <chip.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+ stm32_configgpio(GPIO_SPI_CS_MPU);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+
+ stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
+ stm32_configgpio(GPIO_EXTI_MAG_DRDY);
+ stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
+ stm32_configgpio(GPIO_EXTI_MPU_DRDY);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI_CS_FRAM);
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
+#endif
+}
+
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ break;
+
+ case PX4_SPIDEV_MPU:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_usb.c b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
new file mode 100644
index 000000000..f329e06ff
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_usb.c
+ *
+ * Board-specific USB functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include <up_arch.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ /* XXX We only support device mode
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io-v1/board_config.h
index 6638e715e..1be4877ba 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io-v1/board_config.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file px4io_internal.h
+ * @file board_config.h
*
* PX4IO hardware definitions.
*/
@@ -47,7 +47,9 @@
#include <nuttx/compiler.h>
#include <stdint.h>
+/* these headers are not C++ safe */
#include <stm32.h>
+#include <arch/board/board.h>
/************************************************************************************
* Definitions
@@ -56,11 +58,11 @@
/* PX4IO GPIOs **********************************************************************/
/* LEDs */
-#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
-#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
-#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
+#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
/* Safety switch button *************************************************************/
@@ -83,3 +85,11 @@
#define GPIO_ADC_VBATT (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_ADC_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_CNF_INPULLUP|GPIO_PORTE|GPIO_PIN9)
diff --git a/src/drivers/boards/px4io/module.mk b/src/drivers/boards/px4io-v1/module.mk
index 2601a1c15..2601a1c15 100644
--- a/src/drivers/boards/px4io/module.mk
+++ b/src/drivers/boards/px4io-v1/module.mk
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io-v1/px4io_init.c
index 15c59e423..8292da9e1 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io-v1/px4io_init.c
@@ -55,7 +55,7 @@
#include <nuttx/arch.h>
#include "stm32.h"
-#include "px4io_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io-v1/px4io_pwm_servo.c
index 6df470da6..6df470da6 100644
--- a/src/drivers/boards/px4io/px4io_pwm_servo.c
+++ b/src/drivers/boards/px4io-v1/px4io_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
new file mode 100644
index 000000000..ef9bb5cad
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -0,0 +1,138 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 board_config.h
+ *
+ * PX4IOV2 internal definitions
+ */
+
+#pragma once
+
+/******************************************************************************
+ * Included Files
+ ******************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+/******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/* Configuration **************************************************************/
+
+/******************************************************************************
+ * Serial
+ ******************************************************************************/
+#define PX4FMU_SERIAL_BASE STM32_USART2_BASE
+#define PX4FMU_SERIAL_VECTOR STM32_IRQ_USART2
+#define PX4FMU_SERIAL_TX_GPIO GPIO_USART2_TX
+#define PX4FMU_SERIAL_RX_GPIO GPIO_USART2_RX
+#define PX4FMU_SERIAL_TX_DMA DMACHAN_USART2_TX
+#define PX4FMU_SERIAL_RX_DMA DMACHAN_USART2_RX
+#define PX4FMU_SERIAL_CLOCK STM32_PCLK1_FREQUENCY
+#define PX4FMU_SERIAL_BITRATE 1500000
+
+/******************************************************************************
+ * GPIOS
+ ******************************************************************************/
+
+/* LEDS **********************************************************************/
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
+
+/* Safety switch button *******************************************************/
+
+#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
+
+/* Power switch controls ******************************************************/
+
+#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
+
+#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+
+/* Analog inputs **************************************************************/
+
+#define GPIO_ADC_VSERVO (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+
+/* the same rssi signal goes to both an adc and a timer input */
+#define GPIO_ADC_RSSI (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_TIM_RSSI (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+
+/* PWM pins **************************************************************/
+
+#define GPIO_PPM (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
+
+#define GPIO_PWM1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_PWM2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_PWM3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_PWM4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+#define GPIO_PWM5 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_PWM6 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_PWM7 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_PWM8 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+
+/* SBUS pins *************************************************************/
+
+/* XXX these should be UART pins */
+#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_CNF_INPULLUP|GPIO_PORTE|GPIO_PIN9)
+
+/* LED definitions ******************************************************************/
+/* PX4 has two LEDs that we will encode as: */
+
+#define LED_STARTED 0 /* LED? */
+#define LED_HEAPALLOCATE 1 /* LED? */
+#define LED_IRQSENABLED 2 /* LED? + LED? */
+#define LED_STACKCREATED 3 /* LED? */
+#define LED_INIRQ 4 /* LED? + LED? */
+#define LED_SIGNAL 5 /* LED? + LED? */
+#define LED_ASSERTION 6 /* LED? + LED? + LED? */
+#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
+
diff --git a/src/drivers/boards/px4io-v2/module.mk b/src/drivers/boards/px4io-v2/module.mk
new file mode 100644
index 000000000..85f94e8be
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/module.mk
@@ -0,0 +1,6 @@
+#
+# Board-specific startup code for the PX4IOv2
+#
+
+SRCS = px4iov2_init.c \
+ px4iov2_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
new file mode 100644
index 000000000..9f8c0eeb2
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -0,0 +1,158 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4iov2_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+
+#include <stm32.h>
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+
+ /* configure GPIOs */
+
+ /* LEDS - default to off */
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+
+ stm32_configgpio(GPIO_BTN_SAFETY);
+
+ /* spektrum power enable is active high - enable it by default */
+ stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
+
+ stm32_configgpio(GPIO_SERVO_FAULT_DETECT);
+
+ /* RSSI inputs */
+ stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */
+ stm32_configgpio(GPIO_ADC_RSSI);
+
+ /* servo rail voltage */
+ stm32_configgpio(GPIO_ADC_VSERVO);
+
+ stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
+ stm32_configgpio(GPIO_SBUS_OUTPUT);
+
+ /* sbus output enable is active low - disable it by default */
+ stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
+ stm32_configgpio(GPIO_SBUS_OENABLE);
+
+ stm32_configgpio(GPIO_PPM); /* xxx alternate function */
+
+ stm32_gpiowrite(GPIO_PWM1, false);
+ stm32_configgpio(GPIO_PWM1);
+
+ stm32_gpiowrite(GPIO_PWM2, false);
+ stm32_configgpio(GPIO_PWM2);
+
+ stm32_gpiowrite(GPIO_PWM3, false);
+ stm32_configgpio(GPIO_PWM3);
+
+ stm32_gpiowrite(GPIO_PWM4, false);
+ stm32_configgpio(GPIO_PWM4);
+
+ stm32_gpiowrite(GPIO_PWM5, false);
+ stm32_configgpio(GPIO_PWM5);
+
+ stm32_gpiowrite(GPIO_PWM6, false);
+ stm32_configgpio(GPIO_PWM6);
+
+ stm32_gpiowrite(GPIO_PWM7, false);
+ stm32_configgpio(GPIO_PWM7);
+
+ stm32_gpiowrite(GPIO_PWM8, false);
+ stm32_configgpio(GPIO_PWM8);
+}
diff --git a/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
new file mode 100644
index 000000000..4f1b9487c
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4iov2_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include <stdint.h>
+
+#include <drivers/stm32/drv_pwm_servo.h>
+
+#include <arch/board/board.h>
+#include <drivers/drv_pwm_output.h>
+
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM2_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM2EN,
+ .clock_freq = STM32_APB1_TIM2_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM2_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 2,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH4OUT,
+ .timer_index = 2,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp
index 422321850..b157b3f18 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -38,6 +38,7 @@
*/
#include "device.h"
+#include "drivers/drv_device.h"
#include <sys/ioctl.h>
#include <arch/irq.h>
@@ -93,6 +94,7 @@ CDev::CDev(const char *name,
Device(name, irq),
// public
// protected
+ _pub_blocked(false),
// private
_devname(devname),
_registered(false),
@@ -109,23 +111,59 @@ CDev::~CDev()
}
int
-CDev::init()
+CDev::register_class_devname(const char *class_devname)
{
- int ret = OK;
+ if (class_devname == nullptr) {
+ return -EINVAL;
+ }
+ int class_instance = 0;
+ int ret = -ENOSPC;
+ while (class_instance < 4) {
+ if (class_instance == 0) {
+ ret = register_driver(class_devname, &fops, 0666, (void *)this);
+ if (ret == OK) break;
+ } else {
+ char name[32];
+ snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
+ ret = register_driver(name, &fops, 0666, (void *)this);
+ if (ret == OK) break;
+ }
+ class_instance++;
+ }
+ if (class_instance == 4)
+ return ret;
+ return class_instance;
+}
+int
+CDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
+{
+ if (class_instance > 0) {
+ char name[32];
+ snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
+ return unregister_driver(name);
+ }
+ return unregister_driver(class_devname);
+}
+
+int
+CDev::init()
+{
// base class init first
- ret = Device::init();
+ int ret = Device::init();
if (ret != OK)
goto out;
// now register the driver
- ret = register_driver(_devname, &fops, 0666, (void *)this);
+ if (_devname != nullptr) {
+ ret = register_driver(_devname, &fops, 0666, (void *)this);
- if (ret != OK)
- goto out;
+ if (ret != OK)
+ goto out;
- _registered = true;
+ _registered = true;
+ }
out:
return ret;
@@ -220,6 +258,14 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
case DIOC_GETPRIV:
*(void **)(uintptr_t)arg = (void *)this;
return OK;
+ break;
+ case DEVIOCSPUBBLOCK:
+ _pub_blocked = (arg != 0);
+ return OK;
+ break;
+ case DEVIOCGPUBBLOCK:
+ return _pub_blocked;
+ break;
}
return -ENOTTY;
@@ -395,4 +441,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup)
return cdev->poll(filp, fds, setup);
}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 04a5222c3..683455149 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -223,5 +223,22 @@ interrupt(int irq, void *context)
return OK;
}
+int
+Device::read(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::write(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::ioctl(unsigned operation, unsigned &arg)
+{
+ return -ENODEV;
+}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index 7d375aab9..d99f22922 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -69,10 +69,61 @@ class __EXPORT Device
{
public:
/**
+ * Destructor.
+ *
+ * Public so that anonymous devices can be destroyed.
+ */
+ virtual ~Device();
+
+ /**
* Interrupt handler.
*/
virtual void interrupt(void *ctx); /**< interrupt handler */
+ /*
+ * Direct access methods.
+ */
+
+ /**
+ * Initialise the driver and make it ready for use.
+ *
+ * @return OK if the driver initialized OK, negative errno otherwise;
+ */
+ virtual int init();
+
+ /**
+ * Read directly from the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param offset The device address at which to start reading
+ * @param data The buffer into which the read values should be placed.
+ * @param count The number of items to read.
+ * @return The number of items read on success, negative errno otherwise.
+ */
+ virtual int read(unsigned address, void *data, unsigned count);
+
+ /**
+ * Write directly to the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param address The device address at which to start writing.
+ * @param data The buffer from which values should be read.
+ * @param count The number of items to write.
+ * @return The number of items written on success, negative errno otherwise.
+ */
+ virtual int write(unsigned address, void *data, unsigned count);
+
+ /**
+ * Perform a device-specific operation.
+ *
+ * @param operation The operation to perform.
+ * @param arg An argument to the operation.
+ * @return Negative errno on error, OK or positive value on success.
+ */
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
@@ -85,14 +136,6 @@ protected:
*/
Device(const char *name,
int irq = 0);
- ~Device();
-
- /**
- * Initialise the driver and make it ready for use.
- *
- * @return OK if the driver initialised OK.
- */
- virtual int init();
/**
* Enable the device interrupt
@@ -189,7 +232,7 @@ public:
/**
* Destructor
*/
- ~CDev();
+ virtual ~CDev();
virtual int init();
@@ -282,6 +325,7 @@ public:
* Test whether the device is currently open.
*
* This can be used to avoid tearing down a device that is still active.
+ * Note - not virtual, cannot be overridden by a subclass.
*
* @return True if the device is currently open.
*/
@@ -352,6 +396,27 @@ protected:
*/
virtual int close_last(struct file *filp);
+ /**
+ * Register a class device name, automatically adding device
+ * class instance suffix if need be.
+ *
+ * @param class_devname Device class name
+ * @return class_instamce Class instance created, or -errno on failure
+ */
+ virtual int register_class_devname(const char *class_devname);
+
+ /**
+ * Register a class device name, automatically adding device
+ * class instance suffix if need be.
+ *
+ * @param class_devname Device class name
+ * @param class_instance Device class instance from register_class_devname()
+ * @return OK on success, -errno otherwise
+ */
+ virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
+
+ bool _pub_blocked; /**< true if publishing should be blocked */
+
private:
static const unsigned _max_pollwaiters = 8;
@@ -396,9 +461,9 @@ public:
const char *devname,
uint32_t base,
int irq = 0);
- ~PIO();
+ virtual ~PIO();
- int init();
+ virtual int init();
protected:
@@ -407,7 +472,7 @@ protected:
*
* @param offset Register offset in bytes from the base address.
*/
- uint32_t reg(uint32_t offset) {
+ uint32_t reg(uint32_t offset) {
return *(volatile uint32_t *)(_base + offset);
}
@@ -444,4 +509,7 @@ private:
} // namespace device
-#endif /* _DEVICE_DEVICE_H */ \ No newline at end of file
+// class instance for primary driver of each class
+#define CLASS_DEVICE_PRIMARY 0
+
+#endif /* _DEVICE_DEVICE_H */
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index b4a9cdd53..549879352 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev
public:
- /**
- * Get the address
- */
- uint16_t get_address() {
- return _address;
- }
-
+ /**
+ * Get the address
+ */
+ int16_t get_address() { return _address; }
+
protected:
/**
* The number of times a read or write operation will be retried on
@@ -90,7 +88,7 @@ protected:
uint16_t address,
uint32_t frequency,
int irq = 0);
- ~I2C();
+ virtual ~I2C();
virtual int init();
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h
new file mode 100644
index 000000000..a9e22eaa6
--- /dev/null
+++ b/src/drivers/device/ringbuffer.h
@@ -0,0 +1,509 @@
+/****************************************************************************
+ *
+ * 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 ringbuffer.h
+ *
+ * A flexible ringbuffer class.
+ */
+
+#pragma once
+
+class RingBuffer {
+public:
+ RingBuffer(unsigned ring_size, size_t entry_size);
+ virtual ~RingBuffer();
+
+ /**
+ * Put an item into the buffer.
+ *
+ * @param val Item to put
+ * @return true if the item was put, false if the buffer is full
+ */
+ bool put(const void *val, size_t val_size = 0);
+
+ bool put(int8_t val);
+ bool put(uint8_t val);
+ bool put(int16_t val);
+ bool put(uint16_t val);
+ bool put(int32_t val);
+ bool put(uint32_t val);
+ bool put(int64_t val);
+ bool put(uint64_t val);
+ bool put(float val);
+ bool put(double val);
+
+ /**
+ * Force an item into the buffer, discarding an older item if there is not space.
+ *
+ * @param val Item to put
+ * @return true if an item was discarded to make space
+ */
+ bool force(const void *val, size_t val_size = 0);
+
+ bool force(int8_t val);
+ bool force(uint8_t val);
+ bool force(int16_t val);
+ bool force(uint16_t val);
+ bool force(int32_t val);
+ bool force(uint32_t val);
+ bool force(int64_t val);
+ bool force(uint64_t val);
+ bool force(float val);
+ bool force(double val);
+
+ /**
+ * Get an item from the buffer.
+ *
+ * @param val Item that was gotten
+ * @return true if an item was got, false if the buffer was empty.
+ */
+ bool get(void *val, size_t val_size = 0);
+
+ bool get(int8_t &val);
+ bool get(uint8_t &val);
+ bool get(int16_t &val);
+ bool get(uint16_t &val);
+ bool get(int32_t &val);
+ bool get(uint32_t &val);
+ bool get(int64_t &val);
+ bool get(uint64_t &val);
+ bool get(float &val);
+ bool get(double &val);
+
+ /*
+ * Get the number of slots free in the buffer.
+ *
+ * @return The number of items that can be put into the buffer before
+ * it becomes full.
+ */
+ unsigned space(void);
+
+ /*
+ * Get the number of items in the buffer.
+ *
+ * @return The number of items that can be got from the buffer before
+ * it becomes empty.
+ */
+ unsigned count(void);
+
+ /*
+ * Returns true if the buffer is empty.
+ */
+ bool empty();
+
+ /*
+ * Returns true if the buffer is full.
+ */
+ bool full();
+
+ /*
+ * Returns the capacity of the buffer, or zero if the buffer could
+ * not be allocated.
+ */
+ unsigned size();
+
+ /*
+ * Empties the buffer.
+ */
+ void flush();
+
+ /*
+ * resize the buffer. This is unsafe to be called while
+ * a producer or consuming is running. Caller is responsible
+ * for any locking needed
+ *
+ * @param new_size new size for buffer
+ * @return true if the resize succeeds, false if
+ * not (allocation error)
+ */
+ bool resize(unsigned new_size);
+
+ /*
+ * printf() some info on the buffer
+ */
+ void print_info(const char *name);
+
+private:
+ unsigned _num_items;
+ const size_t _item_size;
+ char *_buf;
+ volatile unsigned _head; /**< insertion point in _item_size units */
+ volatile unsigned _tail; /**< removal point in _item_size units */
+
+ unsigned _next(unsigned index);
+};
+
+RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
+ _num_items(num_items),
+ _item_size(item_size),
+ _buf(new char[(_num_items+1) * item_size]),
+ _head(_num_items),
+ _tail(_num_items)
+{}
+
+RingBuffer::~RingBuffer()
+{
+ if (_buf != nullptr)
+ delete[] _buf;
+}
+
+unsigned
+RingBuffer::_next(unsigned index)
+{
+ return (0 == index) ? _num_items : (index - 1);
+}
+
+bool
+RingBuffer::empty()
+{
+ return _tail == _head;
+}
+
+bool
+RingBuffer::full()
+{
+ return _next(_head) == _tail;
+}
+
+unsigned
+RingBuffer::size()
+{
+ return (_buf != nullptr) ? _num_items : 0;
+}
+
+void
+RingBuffer::flush()
+{
+ while (!empty())
+ get(NULL);
+}
+
+bool
+RingBuffer::put(const void *val, size_t val_size)
+{
+ unsigned next = _next(_head);
+ if (next != _tail) {
+ if ((val_size == 0) || (val_size > _item_size))
+ val_size = _item_size;
+ memcpy(&_buf[_head * _item_size], val, val_size);
+ _head = next;
+ return true;
+ } else {
+ return false;
+ }
+}
+
+bool
+RingBuffer::put(int8_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint8_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int16_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint16_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int32_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint32_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(int64_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(uint64_t val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(float val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::put(double val)
+{
+ return put(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(const void *val, size_t val_size)
+{
+ bool overwrote = false;
+
+ for (;;) {
+ if (put(val, val_size))
+ break;
+ get(NULL);
+ overwrote = true;
+ }
+ return overwrote;
+}
+
+bool
+RingBuffer::force(int8_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint8_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int16_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint16_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int32_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint32_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(int64_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(uint64_t val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(float val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::force(double val)
+{
+ return force(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(void *val, size_t val_size)
+{
+ if (_tail != _head) {
+ unsigned candidate;
+ unsigned next;
+
+ if ((val_size == 0) || (val_size > _item_size))
+ val_size = _item_size;
+
+ do {
+ /* decide which element we think we're going to read */
+ candidate = _tail;
+
+ /* and what the corresponding next index will be */
+ next = _next(candidate);
+
+ /* go ahead and read from this index */
+ if (val != NULL)
+ memcpy(val, &_buf[candidate * _item_size], val_size);
+
+ /* if the tail pointer didn't change, we got our item */
+ } while (!__sync_bool_compare_and_swap(&_tail, candidate, next));
+
+ return true;
+ } else {
+ return false;
+ }
+}
+
+bool
+RingBuffer::get(int8_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint8_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(int16_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint16_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(int32_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint32_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(int64_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(uint64_t &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(float &val)
+{
+ return get(&val, sizeof(val));
+}
+
+bool
+RingBuffer::get(double &val)
+{
+ return get(&val, sizeof(val));
+}
+
+unsigned
+RingBuffer::space(void)
+{
+ unsigned tail, head;
+
+ /*
+ * Make a copy of the head/tail pointers in a fashion that
+ * may err on the side of under-estimating the free space
+ * in the buffer in the case that the buffer is being updated
+ * asynchronously with our check.
+ * If the head pointer changes (reducing space) while copying,
+ * re-try the copy.
+ */
+ do {
+ head = _head;
+ tail = _tail;
+ } while (head != _head);
+
+ return (tail >= head) ? (_num_items - (tail - head)) : (head - tail - 1);
+}
+
+unsigned
+RingBuffer::count(void)
+{
+ /*
+ * Note that due to the conservative nature of space(), this may
+ * over-estimate the number of items in the buffer.
+ */
+ return _num_items - space();
+}
+
+bool
+RingBuffer::resize(unsigned new_size)
+{
+ char *old_buffer;
+ char *new_buffer = new char [(new_size+1) * _item_size];
+ if (new_buffer == nullptr) {
+ return false;
+ }
+ old_buffer = _buf;
+ _buf = new_buffer;
+ _num_items = new_size;
+ _head = new_size;
+ _tail = new_size;
+ delete[] old_buffer;
+ return true;
+}
+
+void
+RingBuffer::print_info(const char *name)
+{
+ printf("%s %u/%u (%u/%u @ %p)\n",
+ name,
+ _num_items,
+ _num_items * _item_size,
+ _head,
+ _tail,
+ _buf);
+}
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index 8fffd60cb..fed6c312c 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -67,6 +67,7 @@ SPI::SPI(const char *name,
CDev(name, devname, irq),
// public
// protected
+ locking_mode(LOCK_PREEMPTION),
// private
_bus(bus),
_device(device),
@@ -132,13 +133,25 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
+ irqstate_t state;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
- /* do common setup */
- if (!up_interrupt_context())
- SPI_LOCK(_dev, true);
+ /* lock the bus as required */
+ if (!up_interrupt_context()) {
+ switch (locking_mode) {
+ default:
+ case LOCK_PREEMPTION:
+ state = irqsave();
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, true);
+ break;
+ case LOCK_NONE:
+ break;
+ }
+ }
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
@@ -151,10 +164,27 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context())
- SPI_LOCK(_dev, false);
+ if (!up_interrupt_context()) {
+ switch (locking_mode) {
+ default:
+ case LOCK_PREEMPTION:
+ irqrestore(state);
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ break;
+ }
+ }
return OK;
}
+void
+SPI::set_frequency(uint32_t frequency)
+{
+ _frequency = frequency;
+}
+
} // namespace device
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index d2d01efb3..299575dc5 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -71,7 +71,7 @@ protected:
enum spi_mode_e mode,
uint32_t frequency,
int irq = 0);
- ~SPI();
+ virtual ~SPI();
virtual int init();
@@ -101,6 +101,28 @@ protected:
*/
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
+ /**
+ * Set the SPI bus frequency
+ * This is used to change frequency on the fly. Some sensors
+ * (such as the MPU6000) need a lower frequency for setup
+ * registers and can handle higher frequency for sensor
+ * value registers
+ *
+ * @param frequency Frequency to set (Hz)
+ */
+ void set_frequency(uint32_t frequency);
+
+ /**
+ * Locking modes supported by the driver.
+ */
+ enum LockMode {
+ LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
+ LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
+ LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
+ };
+
+ LockMode locking_mode; /**< selected locking mode */
+
private:
int _bus;
enum spi_dev_e _device;
diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h
index 794de584b..7d93ed938 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Accelerometer driver interface.
+ * @file drv_accel.h
+ *
+ * Accelerometer driver interface.
*/
#ifndef _DRV_ACCEL_H
@@ -52,6 +54,7 @@
*/
struct accel_report {
uint64_t timestamp;
+ uint64_t error_count;
float x; /**< acceleration in the NED X board axis in m/s^2 */
float y; /**< acceleration in the NED Y board axis in m/s^2 */
float z; /**< acceleration in the NED Z board axis in m/s^2 */
@@ -65,7 +68,7 @@ struct accel_report {
int16_t temperature_raw;
};
-/** accel scaling factors; Vout = (Vin * Vscale) + Voffset */
+/** accel scaling factors; Vout = Vscale * (Vin + Voffset) */
struct accel_scale {
float x_offset;
float x_scale;
diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h
index bffc35c62..78f31495d 100644
--- a/src/drivers/drv_airspeed.h
+++ b/src/drivers/drv_airspeed.h
@@ -32,7 +32,10 @@
****************************************************************************/
/**
- * @file Airspeed driver interface.
+ * @file drv_airspeed.h
+ *
+ * Airspeed driver interface.
+ *
* @author Simon Wilks
*/
@@ -57,5 +60,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/drv_baro.h b/src/drivers/drv_baro.h
index 176f798c0..e2f0137ae 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Barometric pressure sensor driver interface.
+ * @file drv_baro.h
+ *
+ * Barometric pressure sensor driver interface.
*/
#ifndef _DRV_BARO_H
@@ -55,6 +57,7 @@ struct baro_report {
float altitude;
float temperature;
uint64_t timestamp;
+ uint64_t error_count;
};
/*
diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h
new file mode 100644
index 000000000..b310beb74
--- /dev/null
+++ b/src/drivers/drv_device.h
@@ -0,0 +1,62 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_device.h
+ *
+ * Generic device / sensor interface.
+ */
+
+#ifndef _DRV_DEVICE_H
+#define _DRV_DEVICE_H
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#include "drv_sensor.h"
+#include "drv_orb_dev.h"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _DEVICEIOCBASE (0x100)
+#define _DEVICEIOC(_n) (_IOC(_DEVICEIOCBASE, _n))
+
+/** ask device to stop publishing */
+#define DEVIOCSPUBBLOCK _DEVICEIOC(0)
+
+/** check publication block status */
+#define DEVIOCGPUBBLOCK _DEVICEIOC(1)
+
+#endif /* _DRV_DEVICE_H */
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index 7e3998fca..f60964c2b 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 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
@@ -46,7 +46,7 @@
/*
* PX4FMU GPIO numbers.
*
- * For shared pins, alternate function 1 selects the non-GPIO mode
+ * For shared pins, alternate function 1 selects the non-GPIO mode
* (USART2, CAN2, etc.)
*/
# define GPIO_EXT_1 (1<<0) /**< high-power GPIO 1 */
@@ -59,48 +59,47 @@
# define GPIO_CAN_RX (1<<7) /**< CAN2 RX */
/**
- * Default GPIO device - other devices may also support this protocol if
- * they also export GPIO-like things. This is always the GPIOs on the
- * main board.
+ * Device paths for things that support the GPIO ioctl protocol.
*/
-# define GPIO_DEVICE_PATH "/dev/px4fmu"
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+# define PX4IO_DEVICE_PATH "/dev/px4io"
#endif
-#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
/*
- * PX4IO GPIO numbers.
+ * PX4FMUv2 GPIO numbers.
*
- * XXX note that these are here for reference/future use; currently
- * there is no good way to wire these up without a common STM32 GPIO
- * driver, which isn't implemented yet.
+ * There are no alternate functions on this board.
*/
-/* outputs */
-# define GPIO_ACC1_POWER (1<<0) /**< accessory power 1 */
-# define GPIO_ACC2_POWER (1<<1) /**< accessory power 2 */
-# define GPIO_SERVO_POWER (1<<2) /**< servo power */
-# define GPIO_RELAY1 (1<<3) /**< relay 1 */
-# define GPIO_RELAY2 (1<<4) /**< relay 2 */
-# define GPIO_LED_BLUE (1<<5) /**< blue LED */
-# define GPIO_LED_AMBER (1<<6) /**< amber/red LED */
-# define GPIO_LED_SAFETY (1<<7) /**< safety LED */
-
-/* inputs */
-# define GPIO_ACC_OVERCURRENT (1<<8) /**< accessory 1/2 overcurrent detect */
-# define GPIO_SERVO_OVERCURRENT (1<<9) /**< servo overcurrent detect */
-# define GPIO_SAFETY_BUTTON (1<<10) /**< safety button pressed */
+# define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
+# define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
+# define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
+# define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
+# define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
+# define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
+
+# define GPIO_5V_PERIPH_EN (1<<6) /**< PA8 - !VDD_5V_PERIPH_EN */
+# define GPIO_3V3_SENSORS_EN (1<<7) /**< PE3 - VDD_3V3_SENSORS_EN */
+# define GPIO_BRICK_VALID (1<<8) /**< PB5 - !VDD_BRICK_VALID */
+# define GPIO_SERVO_VALID (1<<9) /**< PB7 - !VDD_SERVO_VALID */
+# define GPIO_5V_HIPOWER_OC (1<<10) /**< PE10 - !VDD_5V_HIPOWER_OC */
+# define GPIO_5V_PERIPH_OC (1<<11) /**< PE10 - !VDD_5V_PERIPH_OC */
/**
- * Default GPIO device - other devices may also support this protocol if
- * they also export GPIO-like things. This is always the GPIOs on the
- * main board.
+ * Device paths for things that support the GPIO ioctl protocol.
*/
-# define GPIO_DEVICE_PATH "/dev/px4io"
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+# define PX4IO_DEVICE_PATH "/dev/px4io"
#endif
-#ifndef GPIO_DEVICE_PATH
-# error No GPIO support for this board.
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+/* no GPIO driver on the PX4IOv1 board */
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+/* no GPIO driver on the PX4IOv2 board */
#endif
/*
@@ -145,4 +144,6 @@
/** read all the GPIOs and return their values in *(uint32_t *)arg */
#define GPIO_GET GPIOC(12)
+#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
+
#endif /* _DRV_GPIO_H */ \ No newline at end of file
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index 1dda8ef0b..06e3535b3 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file GPS driver interface.
+ * @file drv_gps.h
+ *
+ * GPS driver interface.
*/
#ifndef _DRV_GPS_H
@@ -51,8 +53,7 @@
typedef enum {
GPS_DRIVER_MODE_NONE = 0,
GPS_DRIVER_MODE_UBX,
- GPS_DRIVER_MODE_MTK,
- GPS_DRIVER_MODE_NMEA,
+ GPS_DRIVER_MODE_MTK
} gps_driver_mode_t;
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 1d0fef6fc..2ae8c7058 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Gyroscope driver interface.
+ * @file drv_gyro.h
+ *
+ * Gyroscope driver interface.
*/
#ifndef _DRV_GYRO_H
@@ -52,6 +54,7 @@
*/
struct gyro_report {
uint64_t timestamp;
+ uint64_t error_count;
float x; /**< angular velocity in the NED X board axis in rad/s */
float y; /**< angular velocity in the NED Y board axis in rad/s */
float z; /**< angular velocity in the NED Z board axis in rad/s */
diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h
index 8a99eeca7..d130d68b3 100644
--- a/src/drivers/drv_hrt.h
+++ b/src/drivers/drv_hrt.h
@@ -142,6 +142,20 @@ __EXPORT extern bool hrt_called(struct hrt_call *entry);
__EXPORT extern void hrt_cancel(struct hrt_call *entry);
/*
+ * initialise a hrt_call structure
+ */
+__EXPORT extern void hrt_call_init(struct hrt_call *entry);
+
+/*
+ * delay a hrt_call_every() periodic call by the given number of
+ * microseconds. This should be called from within the callout to
+ * cause the callout to be re-scheduled for a later time. The periodic
+ * callouts will then continue from that new base time at the
+ * previously specified period.
+ */
+__EXPORT extern void hrt_call_delay(struct hrt_call *entry, hrt_abstime delay);
+
+/*
* Initialise the HRT.
*/
__EXPORT extern void hrt_init(void);
diff --git a/src/drivers/drv_led.h b/src/drivers/drv_led.h
index 21044f620..4ce04696e 100644
--- a/src/drivers/drv_led.h
+++ b/src/drivers/drv_led.h
@@ -54,12 +54,13 @@
#define LED_ON _IOC(_LED_BASE, 0)
#define LED_OFF _IOC(_LED_BASE, 1)
+#define LED_TOGGLE _IOC(_LED_BASE, 2)
__BEGIN_DECLS
/*
* Initialise the LED driver.
*/
-__EXPORT extern void drv_led_start(void);
+__EXPORT void drv_led_start(void);
__END_DECLS
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 9aab995a1..06107bd3d 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -54,6 +54,7 @@
*/
struct mag_report {
uint64_t timestamp;
+ uint64_t error_count;
float x;
float y;
float z;
@@ -90,25 +91,37 @@ ORB_DECLARE(sensor_mag);
/** set the mag internal sample rate to at least (arg) Hz */
#define MAGIOCSSAMPLERATE _MAGIOC(0)
+/** return the mag internal sample rate in Hz */
+#define MAGIOCGSAMPLERATE _MAGIOC(1)
+
/** set the mag internal lowpass filter to no lower than (arg) Hz */
-#define MAGIOCSLOWPASS _MAGIOC(1)
+#define MAGIOCSLOWPASS _MAGIOC(2)
+
+/** return the mag internal lowpass filter in Hz */
+#define MAGIOCGLOWPASS _MAGIOC(3)
/** set the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCSSCALE _MAGIOC(2)
+#define MAGIOCSSCALE _MAGIOC(4)
/** copy the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCGSCALE _MAGIOC(3)
+#define MAGIOCGSCALE _MAGIOC(5)
/** set the measurement range to handle (at least) arg Gauss */
-#define MAGIOCSRANGE _MAGIOC(4)
+#define MAGIOCSRANGE _MAGIOC(6)
+
+/** return the current mag measurement range in Gauss */
+#define MAGIOCGRANGE _MAGIOC(7)
/** perform self-calibration, update scale factors to canonical units */
-#define MAGIOCCALIBRATE _MAGIOC(5)
+#define MAGIOCCALIBRATE _MAGIOC(8)
/** excite strap */
-#define MAGIOCEXSTRAP _MAGIOC(6)
+#define MAGIOCEXSTRAP _MAGIOC(9)
/** perform self test and report status */
-#define MAGIOCSELFTEST _MAGIOC(7)
+#define MAGIOCSELFTEST _MAGIOC(10)
+
+/** determine if mag is external or onboard */
+#define MAGIOCGEXTERNAL _MAGIOC(11)
#endif /* _DRV_MAG_H */
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 56af71059..7a93e513e 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -65,6 +65,36 @@ __BEGIN_DECLS
#define PWM_OUTPUT_MAX_CHANNELS 16
/**
+ * Lowest minimum PWM in us
+ */
+#define PWM_LOWEST_MIN 900
+
+/**
+ * Default minimum PWM in us
+ */
+#define PWM_DEFAULT_MIN 1000
+
+/**
+ * Highest PWM allowed as the minimum PWM
+ */
+#define PWM_HIGHEST_MIN 1300
+
+/**
+ * Highest maximum PWM in us
+ */
+#define PWM_HIGHEST_MAX 2100
+
+/**
+ * Default maximum PWM in us
+ */
+#define PWM_DEFAULT_MAX 2000
+
+/**
+ * Lowest PWM allowed as the maximum PWM
+ */
+#define PWM_LOWEST_MAX 1700
+
+/**
* Servo output signal type, value is actual servo output pulse
* width in microseconds.
*/
@@ -79,6 +109,7 @@ typedef uint16_t servo_position_t;
struct pwm_output_values {
/** desired pulse widths for each of the supported channels */
servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
+ unsigned channel_count;
};
/*
@@ -100,20 +131,81 @@ ORB_DECLARE(output_pwm);
/** disarm all servo outputs (stop generating pulses) */
#define PWM_SERVO_DISARM _IOC(_PWM_SERVO_BASE, 1)
+/** get default servo update rate */
+#define PWM_SERVO_GET_DEFAULT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+
/** set alternate servo update rate */
-#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 3)
+
+/** get alternate servo update rate */
+#define PWM_SERVO_GET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
/** get the number of servos in *(unsigned *)arg */
-#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 3)
+#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 5)
/** selects servo update rates, one bit per servo. 0 = default (50Hz), 1 = alternate */
-#define PWM_SERVO_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
+#define PWM_SERVO_SET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 6)
+
+/** check the selected update rates */
+#define PWM_SERVO_GET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 7)
/** set the 'ARM ok' bit, which activates the safety switch */
-#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 5)
+#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 8)
/** clear the 'ARM ok' bit, which deactivates the safety switch */
-#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 6)
+#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 9)
+
+/** start DSM bind */
+#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 10)
+
+#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
+#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
+#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
+
+/** power up DSM receiver */
+#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
+
+/** set the PWM value for failsafe */
+#define PWM_SERVO_SET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 12)
+
+/** get the PWM value for failsafe */
+#define PWM_SERVO_GET_FAILSAFE_PWM _IOC(_PWM_SERVO_BASE, 13)
+
+/** set the PWM value when disarmed - should be no PWM (zero) by default */
+#define PWM_SERVO_SET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 14)
+
+/** get the PWM value when disarmed */
+#define PWM_SERVO_GET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 15)
+
+/** set the minimum PWM value the output will send */
+#define PWM_SERVO_SET_MIN_PWM _IOC(_PWM_SERVO_BASE, 16)
+
+/** get the minimum PWM value the output will send */
+#define PWM_SERVO_GET_MIN_PWM _IOC(_PWM_SERVO_BASE, 17)
+
+/** set the maximum PWM value the output will send */
+#define PWM_SERVO_SET_MAX_PWM _IOC(_PWM_SERVO_BASE, 18)
+
+/** get the maximum PWM value the output will send */
+#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 19)
+
+/** set the number of servos in (unsigned)arg - allows change of
+ * split between servos and GPIO */
+#define PWM_SERVO_SET_COUNT _IOC(_PWM_SERVO_BASE, 20)
+
+/** set the lockdown override flag to enable outputs in HIL */
+#define PWM_SERVO_SET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 21)
+
+/** get the lockdown override flag to enable outputs in HIL */
+#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
+
+/*
+ *
+ *
+ * WARNING WARNING WARNING! DO NOT EXCEED 31 IN IOC INDICES HERE!
+ *
+ *
+ */
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index 03a82ec5d..cf91f7030 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -52,6 +52,7 @@
*/
struct range_finder_report {
uint64_t timestamp;
+ uint64_t error_count;
float distance; /** in meters */
uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
};
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 4decc324e..20763e265 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -32,8 +32,9 @@
****************************************************************************/
/**
- * @file R/C input interface.
+ * @file drv_rc_input.h
*
+ * R/C input interface.
*/
#ifndef _DRV_RC_INPUT_H
@@ -62,6 +63,11 @@
#define RC_INPUT_MAX_CHANNELS 18
/**
+ * Maximum RSSI value
+ */
+#define RC_INPUT_RSSI_MAX 255
+
+/**
* Input signal type, value is a control position from zero to 100
* percent.
*/
@@ -82,12 +88,52 @@ enum RC_INPUT_SOURCE {
* on the board involved.
*/
struct rc_input_values {
- /** decoding time */
- uint64_t timestamp;
+ /** publication time */
+ uint64_t timestamp_publication;
+
+ /** last valid reception time */
+ uint64_t timestamp_last_signal;
/** number of channels actually being seen */
uint32_t channel_count;
+ /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 255: full reception */
+ int32_t rssi;
+
+ /**
+ * explicit failsafe flag: true on TX failure or TX out of range , false otherwise.
+ * Only the true state is reliable, as there are some (PPM) receivers on the market going
+ * into failsafe without telling us explicitly.
+ * */
+ bool rc_failsafe;
+
+ /**
+ * RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise.
+ * True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems.
+ * Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
+ * */
+ bool rc_lost;
+
+ /**
+ * Number of lost RC frames.
+ * Note: intended purpose: observe the radio link quality if RSSI is not available
+ * This value must not be used to trigger any failsafe-alike funtionality.
+ * */
+ uint16_t rc_lost_frame_count;
+
+ /**
+ * Number of total RC frames.
+ * Note: intended purpose: observe the radio link quality if RSSI is not available
+ * This value must not be used to trigger any failsafe-alike funtionality.
+ * */
+ uint16_t rc_total_frame_count;
+
+ /**
+ * Length of a single PPM frame.
+ * Zero for non-PPM systems
+ */
+ uint16_t rc_ppm_frame_length;
+
/** Input source */
enum RC_INPUT_SOURCE input_source;
@@ -103,8 +149,12 @@ ORB_DECLARE(input_rc);
#define _RC_INPUT_BASE 0x2b00
/** Fetch R/C input values into (rc_input_values *)arg */
-
#define RC_INPUT_GET _IOC(_RC_INPUT_BASE, 0)
+/** Enable RSSI input via ADC */
+#define RC_INPUT_ENABLE_RSSI_ANALOG _IOC(_RC_INPUT_BASE, 1)
+
+/** Enable RSSI input via PWM signal */
+#define RC_INPUT_ENABLE_RSSI_PWM _IOC(_RC_INPUT_BASE, 2)
#endif /* _DRV_RC_INPUT_H */
diff --git a/src/drivers/drv_rgbled.h b/src/drivers/drv_rgbled.h
new file mode 100644
index 000000000..07c6186dd
--- /dev/null
+++ b/src/drivers/drv_rgbled.h
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-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 drv_rgbled.h
+ *
+ * RGB led device API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+/* more devices will be 1, 2, etc */
+#define RGBLED_DEVICE_PATH "/dev/rgbled0"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _RGBLEDIOCBASE (0x2900)
+#define _RGBLEDIOC(_n) (_IOC(_RGBLEDIOCBASE, _n))
+
+/** play the named script in *(char *)arg, repeating forever */
+#define RGBLED_PLAY_SCRIPT_NAMED _RGBLEDIOC(1)
+
+/** play the numbered script in (arg), repeating forever */
+#define RGBLED_PLAY_SCRIPT _RGBLEDIOC(2)
+
+/**
+ * Set the user script; (arg) is a pointer to an array of script lines,
+ * where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
+ *
+ * The script is terminated by a zero command.
+ */
+#define RGBLED_SET_USER_SCRIPT _RGBLEDIOC(3)
+
+/** set constant RGB values */
+#define RGBLED_SET_RGB _RGBLEDIOC(4)
+
+/** set color */
+#define RGBLED_SET_COLOR _RGBLEDIOC(5)
+
+/** set blink speed */
+#define RGBLED_SET_MODE _RGBLEDIOC(6)
+
+/** set pattern */
+#define RGBLED_SET_PATTERN _RGBLEDIOC(7)
+
+
+/*
+ structure passed to RGBLED_SET_RGB ioctl()
+ Note that the driver scales the brightness to 0 to 255, regardless
+ of the hardware scaling
+ */
+typedef struct {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+} rgbled_rgbset_t;
+
+/* enum passed to RGBLED_SET_COLOR ioctl()*/
+typedef enum {
+ RGBLED_COLOR_OFF,
+ RGBLED_COLOR_RED,
+ RGBLED_COLOR_YELLOW,
+ RGBLED_COLOR_PURPLE,
+ RGBLED_COLOR_GREEN,
+ RGBLED_COLOR_BLUE,
+ RGBLED_COLOR_WHITE,
+ RGBLED_COLOR_AMBER,
+ RGBLED_COLOR_DIM_RED,
+ RGBLED_COLOR_DIM_YELLOW,
+ RGBLED_COLOR_DIM_PURPLE,
+ RGBLED_COLOR_DIM_GREEN,
+ RGBLED_COLOR_DIM_BLUE,
+ RGBLED_COLOR_DIM_WHITE,
+ RGBLED_COLOR_DIM_AMBER
+} rgbled_color_t;
+
+/* enum passed to RGBLED_SET_MODE ioctl()*/
+typedef enum {
+ RGBLED_MODE_OFF,
+ RGBLED_MODE_ON,
+ RGBLED_MODE_BLINK_SLOW,
+ RGBLED_MODE_BLINK_NORMAL,
+ RGBLED_MODE_BLINK_FAST,
+ RGBLED_MODE_BREATHE,
+ RGBLED_MODE_PATTERN
+} rgbled_mode_t;
+
+#define RGBLED_PATTERN_LENGTH 20
+
+typedef struct {
+ rgbled_color_t color[RGBLED_PATTERN_LENGTH];
+ unsigned duration[RGBLED_PATTERN_LENGTH];
+} rgbled_pattern_t;
diff --git a/src/drivers/drv_sbus.h b/src/drivers/drv_sbus.h
new file mode 100644
index 000000000..927c904ec
--- /dev/null
+++ b/src/drivers/drv_sbus.h
@@ -0,0 +1,58 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_sbus.h
+ *
+ * Futaba S.BUS / S.BUS 2 compatible interface.
+ */
+
+#ifndef _DRV_SBUS_H
+#define _DRV_SBUS_H
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#include "drv_orb_dev.h"
+
+/**
+ * Path for the default S.BUS device
+ */
+#define SBUS_DEVICE_PATH "/dev/sbus"
+
+#define _SBUS_BASE 0x2c00
+
+/** Enable S.BUS version 1 / 2 output (0 to disable) */
+#define SBUS_SET_PROTO_VERSION _IOC(_SBUS_BASE, 0)
+
+#endif /* _DRV_SBUS_H */
diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h
index 3a89cab9d..8e8b2c1b9 100644
--- a/src/drivers/drv_sensor.h
+++ b/src/drivers/drv_sensor.h
@@ -32,7 +32,9 @@
****************************************************************************/
/**
- * @file Common sensor API and ioctl definitions.
+ * @file drv_sensor.h
+ *
+ * Common sensor API and ioctl definitions.
*/
#ifndef _DRV_SENSOR_H
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index 0c6afc64c..cb5fd53a5 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -31,7 +31,9 @@
*
****************************************************************************/
-/*
+/**
+ * @file drv_tone_alarm.h
+ *
* Driver for the PX4 audio alarm port, /dev/tone_alarm.
*
* The tone_alarm driver supports a set of predefined "alarm"
@@ -60,6 +62,8 @@
#include <sys/ioctl.h>
+#define TONEALARM_DEVICE_PATH "/dev/tone_alarm"
+
#define _TONE_ALARM_BASE 0x7400
#define TONE_SET_ALARM _IOC(_TONE_ALARM_BASE, 1)
@@ -125,4 +129,25 @@ enum tone_pitch {
TONE_NOTE_MAX
};
+enum {
+ TONE_STOP_TUNE = 0,
+ TONE_STARTUP_TUNE,
+ TONE_ERROR_TUNE,
+ TONE_NOTIFY_POSITIVE_TUNE,
+ TONE_NOTIFY_NEUTRAL_TUNE,
+ TONE_NOTIFY_NEGATIVE_TUNE,
+ /* Do not include these unused tunes
+ TONE_CHARGE_TUNE,
+ TONE_DIXIE_TUNE,
+ TONE_CUCURACHA_TUNE,
+ TONE_YANKEE_TUNE,
+ TONE_DAISY_TUNE,
+ TONE_WILLIAM_TELL_TUNE, */
+ TONE_ARMING_WARNING_TUNE,
+ TONE_BATTERY_WARNING_SLOW_TUNE,
+ TONE_BATTERY_WARNING_FAST_TUNE,
+ TONE_GPS_WARNING_TUNE,
+ TONE_NUMBER_OF_TUNES
+};
+
#endif /* DRV_TONE_ALARM_H_ */
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index e50395e47..8bbef5cfa 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.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
@@ -37,7 +37,7 @@
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -59,7 +59,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
@@ -68,357 +68,54 @@
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
+#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
-
-/* Default I2C bus */
-#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
+#include <drivers/airspeed/airspeed.h>
/* I2C bus address */
-#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
+#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
/* Register address */
-#define READ_CMD 0x07 /* Read the data */
-
+#define READ_CMD 0x07 /* Read the data */
+
/**
- * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * 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 12
+#define MIN_ACCURATE_DIFF_PRES_PA 0
/* 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;
- int _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();
+ virtual void cycle();
+ virtual int measure();
+ virtual 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);
-
-
};
-/* 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),
- _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;
-
- 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
@@ -432,14 +129,11 @@ ETSAirspeed::measure()
uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
- return ret;
}
- ret = OK;
-
+
return ret;
}
@@ -447,98 +141,64 @@ int
ETSAirspeed::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);
+ perf_count(_comms_errors);
return ret;
}
-
+
uint16_t diff_pres_pa = val[1] << 8 | val[0];
+ if (diff_pres_pa == 0) {
+ // a zero value means the pressure sensor cannot give us a
+ // value. We need to return, and not report a value or the
+ // caller could end up using this value as part of an
+ // average
+ perf_count(_comms_errors);
+ log("zero value from sensor");
+ return -1;
+ }
- param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
-
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+ if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
} else {
- diff_pres_pa -= _diff_pres_offset;
+ 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;
+ if (diff_pres_pa > _max_differential_pressure_pa) {
+ _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);
+ // XXX we may want to smooth out the readings to remove noise.
+ differential_pressure_s report;
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.differential_pressure_pa = (float)diff_pres_pa;
+ report.voltage = 0;
+ report.max_differential_pressure_pa = _max_differential_pressure_pa;
+
+ if (_airspeed_pub > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
}
+ new_report(report);
+
/* notify anyone waiting for data */
poll_notify(POLLIN);
ret = OK;
perf_end(_sample_perf);
-
- 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();
+ return ret;
}
void
@@ -549,7 +209,7 @@ ETSAirspeed::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ perf_count(_comms_errors);
/* restart the measurement state machine */
start();
return;
@@ -566,7 +226,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));
@@ -584,22 +244,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.
*/
@@ -637,7 +286,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 */
@@ -653,8 +302,7 @@ start(int i2c_bus)
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -668,15 +316,14 @@ fail:
void
stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -732,6 +379,10 @@ test()
warnx("diff pressure: %d pa", report.differential_pressure_pa);
}
+ /* reset the sensor polling to its default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
+ errx(1, "failed to set default rate");
+
errx(0, "PASS");
}
@@ -773,14 +424,14 @@ info()
} // namespace
-static void
-ets_airspeed_usage()
+static void
+ets_airspeed_usage()
{
- fprintf(stderr, "usage: ets_airspeed [options] command\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
@@ -789,6 +440,7 @@ ets_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) {
@@ -802,12 +454,12 @@ ets_airspeed_main(int argc, char *argv[])
*/
if (!strcmp(argv[1], "start"))
ets_airspeed::start(i2c_bus);
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- ets_airspeed::stop();
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ ets_airspeed::stop();
/*
* Test the driver/device.
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/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
new file mode 100644
index 000000000..63b2d2d29
--- /dev/null
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -0,0 +1,289 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ * Author: Stefan Rado <px4@sradonia.net>
+ *
+ * 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 frsky_data.c
+ * @author Stefan Rado <px4@sradonia.net>
+ *
+ * FrSky telemetry implementation.
+ *
+ */
+
+#include "frsky_data.h"
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <arch/math.h>
+#include <geo/geo.h>
+
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_status.h>
+
+/* FrSky sensor hub data IDs */
+#define FRSKY_ID_GPS_ALT_BP 0x01
+#define FRSKY_ID_TEMP1 0x02
+#define FRSKY_ID_RPM 0x03
+#define FRSKY_ID_FUEL 0x04
+#define FRSKY_ID_TEMP2 0x05
+#define FRSKY_ID_VOLTS 0x06
+#define FRSKY_ID_GPS_ALT_AP 0x09
+#define FRSKY_ID_BARO_ALT_BP 0x10
+#define FRSKY_ID_GPS_SPEED_BP 0x11
+#define FRSKY_ID_GPS_LONG_BP 0x12
+#define FRSKY_ID_GPS_LAT_BP 0x13
+#define FRSKY_ID_GPS_COURS_BP 0x14
+#define FRSKY_ID_GPS_DAY_MONTH 0x15
+#define FRSKY_ID_GPS_YEAR 0x16
+#define FRSKY_ID_GPS_HOUR_MIN 0x17
+#define FRSKY_ID_GPS_SEC 0x18
+#define FRSKY_ID_GPS_SPEED_AP 0x19
+#define FRSKY_ID_GPS_LONG_AP 0x1A
+#define FRSKY_ID_GPS_LAT_AP 0x1B
+#define FRSKY_ID_GPS_COURS_AP 0x1C
+#define FRSKY_ID_BARO_ALT_AP 0x21
+#define FRSKY_ID_GPS_LONG_EW 0x22
+#define FRSKY_ID_GPS_LAT_NS 0x23
+#define FRSKY_ID_ACCEL_X 0x24
+#define FRSKY_ID_ACCEL_Y 0x25
+#define FRSKY_ID_ACCEL_Z 0x26
+#define FRSKY_ID_CURRENT 0x28
+#define FRSKY_ID_VARIO 0x30
+#define FRSKY_ID_VFAS 0x39
+#define FRSKY_ID_VOLTS_BP 0x3A
+#define FRSKY_ID_VOLTS_AP 0x3B
+
+#define frac(f) (f - (int)f)
+
+static int battery_sub = -1;
+static int sensor_sub = -1;
+static int global_position_sub = -1;
+static int vehicle_status_sub = -1;
+
+/**
+ * Initializes the uORB subscriptions.
+ */
+void frsky_init()
+{
+ battery_sub = orb_subscribe(ORB_ID(battery_status));
+ global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+}
+
+/**
+ * Sends a 0x5E start/stop byte.
+ */
+static void frsky_send_startstop(int uart)
+{
+ static const uint8_t c = 0x5E;
+ write(uart, &c, sizeof(c));
+}
+
+/**
+ * Sends one byte, performing byte-stuffing if necessary.
+ */
+static void frsky_send_byte(int uart, uint8_t value)
+{
+ const uint8_t x5E[] = { 0x5D, 0x3E };
+ const uint8_t x5D[] = { 0x5D, 0x3D };
+
+ switch (value) {
+ case 0x5E:
+ write(uart, x5E, sizeof(x5E));
+ break;
+
+ case 0x5D:
+ write(uart, x5D, sizeof(x5D));
+ break;
+
+ default:
+ write(uart, &value, sizeof(value));
+ break;
+ }
+}
+
+/**
+ * Sends one data id/value pair.
+ */
+static void frsky_send_data(int uart, uint8_t id, int16_t data)
+{
+ /* Cast data to unsigned, because signed shift might behave incorrectly */
+ uint16_t udata = data;
+
+ frsky_send_startstop(uart);
+
+ frsky_send_byte(uart, id);
+ frsky_send_byte(uart, udata); /* LSB */
+ frsky_send_byte(uart, udata >> 8); /* MSB */
+}
+
+/**
+ * Sends frame 1 (every 200ms):
+ * acceleration values, barometer altitude, temperature, battery voltage & current
+ */
+void frsky_send_frame1(int uart)
+{
+ /* get a local copy of the current sensor values */
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+ orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
+
+ /* get a local copy of the battery data */
+ struct battery_status_s battery;
+ memset(&battery, 0, sizeof(battery));
+ orb_copy(ORB_ID(battery_status), battery_sub, &battery);
+
+ /* send formatted frame */
+ frsky_send_data(uart, FRSKY_ID_ACCEL_X,
+ roundf(raw.accelerometer_m_s2[0] * 1000.0f));
+ frsky_send_data(uart, FRSKY_ID_ACCEL_Y,
+ roundf(raw.accelerometer_m_s2[1] * 1000.0f));
+ frsky_send_data(uart, FRSKY_ID_ACCEL_Z,
+ roundf(raw.accelerometer_m_s2[2] * 1000.0f));
+
+ frsky_send_data(uart, FRSKY_ID_BARO_ALT_BP,
+ raw.baro_alt_meter);
+ frsky_send_data(uart, FRSKY_ID_BARO_ALT_AP,
+ roundf(frac(raw.baro_alt_meter) * 100.0f));
+
+ frsky_send_data(uart, FRSKY_ID_TEMP1,
+ roundf(raw.baro_temp_celcius));
+
+ frsky_send_data(uart, FRSKY_ID_VFAS,
+ roundf(battery.voltage_v * 10.0f));
+ frsky_send_data(uart, FRSKY_ID_CURRENT,
+ (battery.current_a < 0) ? 0 : roundf(battery.current_a * 10.0f));
+
+ frsky_send_startstop(uart);
+}
+
+/**
+ * Formats the decimal latitude/longitude to the required degrees/minutes/seconds.
+ */
+static float frsky_format_gps(float dec)
+{
+ float dms_deg = (int) dec;
+ float dec_deg = dec - dms_deg;
+ float dms_min = (int) (dec_deg * 60);
+ float dec_min = (dec_deg * 60) - dms_min;
+ float dms_sec = dec_min * 60;
+
+ return (dms_deg * 100.0f) + dms_min + (dms_sec / 100.0f);
+}
+
+/**
+ * Sends frame 2 (every 1000ms):
+ * GPS course, latitude, longitude, ground speed, GPS altitude, remaining battery level
+ */
+void frsky_send_frame2(int uart)
+{
+ /* get a local copy of the global position data */
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
+ orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_pos);
+
+ /* get a local copy of the vehicle status data */
+ struct vehicle_status_s vehicle_status;
+ memset(&vehicle_status, 0, sizeof(vehicle_status));
+ orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vehicle_status);
+
+ /* send formatted frame */
+ float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
+ char lat_ns = 0, lon_ew = 0;
+ int sec = 0;
+ if (global_pos.valid) {
+ time_t time_gps = global_pos.time_gps_usec / 1000000;
+ struct tm *tm_gps = gmtime(&time_gps);
+
+ course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
+ lat = frsky_format_gps(abs(global_pos.lat) / 10000000.0f);
+ lat_ns = (global_pos.lat < 0) ? 'S' : 'N';
+ lon = frsky_format_gps(abs(global_pos.lon) / 10000000.0f);
+ lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
+ speed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy)
+ * 25.0f / 46.0f;
+ alt = global_pos.alt;
+ sec = tm_gps->tm_sec;
+ }
+
+ frsky_send_data(uart, FRSKY_ID_GPS_COURS_BP, course);
+ frsky_send_data(uart, FRSKY_ID_GPS_COURS_AP, frac(course) * 1000.0f);
+
+ frsky_send_data(uart, FRSKY_ID_GPS_LAT_BP, lat);
+ frsky_send_data(uart, FRSKY_ID_GPS_LAT_AP, frac(lat) * 10000.0f);
+ frsky_send_data(uart, FRSKY_ID_GPS_LAT_NS, lat_ns);
+
+ frsky_send_data(uart, FRSKY_ID_GPS_LONG_BP, lon);
+ frsky_send_data(uart, FRSKY_ID_GPS_LONG_AP, frac(lon) * 10000.0f);
+ frsky_send_data(uart, FRSKY_ID_GPS_LONG_EW, lon_ew);
+
+ frsky_send_data(uart, FRSKY_ID_GPS_SPEED_BP, speed);
+ frsky_send_data(uart, FRSKY_ID_GPS_SPEED_AP, frac(speed) * 100.0f);
+
+ frsky_send_data(uart, FRSKY_ID_GPS_ALT_BP, alt);
+ frsky_send_data(uart, FRSKY_ID_GPS_ALT_AP, frac(alt) * 100.0f);
+
+ frsky_send_data(uart, FRSKY_ID_FUEL,
+ roundf(vehicle_status.battery_remaining * 100.0f));
+
+ frsky_send_data(uart, FRSKY_ID_GPS_SEC, sec);
+
+ frsky_send_startstop(uart);
+}
+
+/**
+ * Sends frame 3 (every 5000ms):
+ * GPS date & time
+ */
+void frsky_send_frame3(int uart)
+{
+ /* get a local copy of the battery data */
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
+ orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_pos);
+
+ /* send formatted frame */
+ time_t time_gps = global_pos.time_gps_usec / 1000000;
+ struct tm *tm_gps = gmtime(&time_gps);
+ uint16_t hour_min = (tm_gps->tm_min << 8) | (tm_gps->tm_hour & 0xff);
+ frsky_send_data(uart, FRSKY_ID_GPS_DAY_MONTH, tm_gps->tm_mday);
+ frsky_send_data(uart, FRSKY_ID_GPS_YEAR, tm_gps->tm_year);
+ frsky_send_data(uart, FRSKY_ID_GPS_HOUR_MIN, hour_min);
+ frsky_send_data(uart, FRSKY_ID_GPS_SEC, tm_gps->tm_sec);
+
+ frsky_send_startstop(uart);
+}
diff --git a/src/drivers/frsky_telemetry/frsky_data.h b/src/drivers/frsky_telemetry/frsky_data.h
new file mode 100644
index 000000000..a7d9eee53
--- /dev/null
+++ b/src/drivers/frsky_telemetry/frsky_data.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ * Author: Stefan Rado <px4@sradonia.net>
+ *
+ * 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 frsky_data.h
+ * @author Stefan Rado <px4@sradonia.net>
+ *
+ * FrSky telemetry implementation.
+ *
+ */
+#ifndef _FRSKY_DATA_H
+#define _FRSKY_DATA_H
+
+// Public functions
+void frsky_init(void);
+void frsky_send_frame1(int uart);
+void frsky_send_frame2(int uart);
+void frsky_send_frame3(int uart);
+
+#endif /* _FRSKY_TELEMETRY_H */
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
new file mode 100644
index 000000000..7b08ca69e
--- /dev/null
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -0,0 +1,266 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ * Author: Stefan Rado <px4@sradonia.net>
+ *
+ * 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 frsky_telemetry.c
+ * @author Stefan Rado <px4@sradonia.net>
+ *
+ * FrSky telemetry implementation.
+ *
+ * This daemon emulates an FrSky sensor hub by periodically sending data
+ * packets to an attached FrSky receiver.
+ *
+ */
+
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <string.h>
+#include <sys/types.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+#include <termios.h>
+
+#include "frsky_data.h"
+
+
+/* thread state */
+static volatile bool thread_should_exit = false;
+static volatile bool thread_running = false;
+static int frsky_task;
+
+/* functions */
+static int frsky_open_uart(const char *uart_name, struct termios *uart_config_original);
+static void usage(void);
+static int frsky_telemetry_thread_main(int argc, char *argv[]);
+__EXPORT int frsky_telemetry_main(int argc, char *argv[]);
+
+
+/**
+ * Opens the UART device and sets all required serial parameters.
+ */
+static int frsky_open_uart(const char *uart_name, struct termios *uart_config_original)
+{
+ /* Open UART */
+ const int uart = open(uart_name, O_WRONLY | O_NOCTTY);
+
+ if (uart < 0) {
+ err(1, "Error opening port: %s", uart_name);
+ }
+
+ /* Back up the original UART configuration to restore it after exit */
+ int termios_state;
+ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
+ warnx("ERROR get termios config %s: %d\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+ /* Fill the struct for the new configuration */
+ struct termios uart_config;
+ tcgetattr(uart, &uart_config);
+
+ /* Disable output post-processing */
+ uart_config.c_oflag &= ~OPOST;
+
+ /* Set baud rate */
+ static const speed_t speed = B9600;
+
+ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ close(uart);
+ return -1;
+ }
+
+ return uart;
+}
+
+/**
+ * Print command usage information
+ */
+static void usage()
+{
+ fprintf(stderr,
+ "usage: frsky_telemetry start [-d <devicename>]\n"
+ " frsky_telemetry stop\n"
+ " frsky_telemetry status\n");
+ exit(1);
+}
+
+/**
+ * The daemon thread.
+ */
+static int frsky_telemetry_thread_main(int argc, char *argv[])
+{
+ /* Default values for arguments */
+ char *device_name = "/dev/ttyS1"; /* USART2 */
+
+ /* Work around some stupidity in task_create's argv handling */
+ argc -= 2;
+ argv += 2;
+
+ int ch;
+ while ((ch = getopt(argc, argv, "d:")) != EOF) {
+ switch (ch) {
+ case 'd':
+ device_name = optarg;
+ break;
+
+ default:
+ usage();
+ break;
+ }
+ }
+
+ /* Print welcome text */
+ warnx("FrSky telemetry interface starting...");
+
+ /* Open UART */
+ struct termios uart_config_original;
+ const int uart = frsky_open_uart(device_name, &uart_config_original);
+
+ if (uart < 0)
+ err(1, "could not open %s", device_name);
+
+ /* Subscribe to topics */
+ frsky_init();
+
+ thread_running = true;
+
+ /* Main thread loop */
+ unsigned int iteration = 0;
+ while (!thread_should_exit) {
+
+ /* Sleep 200 ms */
+ usleep(200000);
+
+ /* Send frame 1 (every 200ms): acceleration values, altitude (vario), temperatures, current & voltages, RPM */
+ frsky_send_frame1(uart);
+
+ /* Send frame 2 (every 1000ms): course, latitude, longitude, speed, altitude (GPS), fuel level */
+ if (iteration % 5 == 0)
+ {
+ frsky_send_frame2(uart);
+ }
+
+ /* Send frame 3 (every 5000ms): date, time */
+ if (iteration % 25 == 0)
+ {
+ frsky_send_frame3(uart);
+
+ iteration = 0;
+ }
+
+ iteration++;
+ }
+
+ /* Reset the UART flags to original state */
+ tcsetattr(uart, TCSANOW, &uart_config_original);
+ close(uart);
+
+ thread_running = false;
+ return 0;
+}
+
+/**
+ * The main command function.
+ * Processes command line arguments and starts the daemon.
+ */
+int frsky_telemetry_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ warnx("missing command");
+ usage();
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ /* this is not an error */
+ if (thread_running)
+ errx(0, "frsky_telemetry already running");
+
+ thread_should_exit = false;
+ frsky_task = task_spawn_cmd("frsky_telemetry",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT,
+ 2048,
+ frsky_telemetry_thread_main,
+ (const char **)argv);
+
+ while (!thread_running) {
+ usleep(200);
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+
+ /* this is not an error */
+ if (!thread_running)
+ errx(0, "frsky_telemetry already stopped");
+
+ thread_should_exit = true;
+
+ while (thread_running) {
+ usleep(200000);
+ warnx(".");
+ }
+
+ warnx("terminated.");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ usage();
+ /* not getting here */
+ return 0;
+}
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
new file mode 100644
index 000000000..1632c74f7
--- /dev/null
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# 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
+# 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.
+#
+############################################################################
+
+#
+# FrSky telemetry application.
+#
+
+MODULE_COMMAND = frsky_telemetry
+
+SRCS = frsky_data.c \
+ frsky_telemetry.c
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 38835418b..a736cbdf6 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -85,7 +85,7 @@ static const int ERROR = -1;
class GPS : public device::CDev
{
public:
- GPS(const char* uart_path);
+ GPS(const char *uart_path, bool fake_gps);
virtual ~GPS();
virtual int init();
@@ -112,6 +112,7 @@ private:
struct vehicle_gps_position_s _report; ///< uORB topic for gps position
orb_advert_t _report_pub; ///< uORB pub for gps position
float _rate; ///< position update rate
+ bool _fake_gps; ///< fake gps output
/**
@@ -156,7 +157,7 @@ GPS *g_dev;
}
-GPS::GPS(const char* uart_path) :
+GPS::GPS(const char *uart_path, bool fake_gps) :
CDev("gps", GPS_DEVICE_PATH),
_task_should_exit(false),
_healthy(false),
@@ -164,7 +165,8 @@ GPS::GPS(const char* uart_path) :
_mode(GPS_DRIVER_MODE_UBX),
_Helper(nullptr),
_report_pub(-1),
- _rate(0.0f)
+ _rate(0.0f),
+ _fake_gps(fake_gps)
{
/* store port name */
strncpy(_port, uart_path, sizeof(_port));
@@ -192,6 +194,7 @@ GPS::~GPS()
/* well, kill it anyway, though this will probably crash */
if (_task != -1)
task_delete(_task);
+
g_dev = nullptr;
}
@@ -263,84 +266,143 @@ GPS::task_main()
/* loop handling received serial bytes and also configuring in between */
while (!_task_should_exit) {
- if (_Helper != nullptr) {
- delete(_Helper);
- /* set to zero to ensure parser is not used while not instantiated */
- _Helper = nullptr;
- }
+ if (_fake_gps) {
+
+ _report.timestamp_position = hrt_absolute_time();
+ _report.lat = (int32_t)47.378301e7f;
+ _report.lon = (int32_t)8.538777e7f;
+ _report.alt = (int32_t)400e3f;
+ _report.timestamp_variance = hrt_absolute_time();
+ _report.s_variance_m_s = 10.0f;
+ _report.p_variance_m = 10.0f;
+ _report.c_variance_rad = 0.1f;
+ _report.fix_type = 3;
+ _report.eph_m = 10.0f;
+ _report.epv_m = 10.0f;
+ _report.timestamp_velocity = hrt_absolute_time();
+ _report.vel_n_m_s = 0.0f;
+ _report.vel_e_m_s = 0.0f;
+ _report.vel_d_m_s = 0.0f;
+ _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
+ _report.cog_rad = 0.0f;
+ _report.vel_ned_valid = true;
+
+ //no time and satellite information simulated
+
+ if (!(_pub_blocked)) {
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
+ }
+
+ usleep(2e5);
+
+ } else {
+
+ if (_Helper != nullptr) {
+ delete(_Helper);
+ /* set to zero to ensure parser is not used while not instantiated */
+ _Helper = nullptr;
+ }
- switch (_mode) {
+ switch (_mode) {
case GPS_DRIVER_MODE_UBX:
_Helper = new UBX(_serial_fd, &_report);
break;
+
case GPS_DRIVER_MODE_MTK:
_Helper = new MTK(_serial_fd, &_report);
break;
- case GPS_DRIVER_MODE_NMEA:
- //_Helper = new NMEA(); //TODO: add NMEA
- break;
+
default:
break;
- }
- unlock();
- if (_Helper->configure(_baudrate) == 0) {
+ }
+
unlock();
- // GPS is obviously detected successfully, reset statistics
- _Helper->reset_update_rates();
+ if (_Helper->configure(_baudrate) == 0) {
+ unlock();
- while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
-// lock();
- /* opportunistic publishing - else invalid data would end up on the bus */
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
- } else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
- }
+ // GPS is obviously detected successfully, reset statistics
+ _Helper->reset_update_rates();
+
+ while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
+ // lock();
+ /* opportunistic publishing - else invalid data would end up on the bus */
+
+ if (!(_pub_blocked)) {
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
- last_rate_count++;
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
+ }
- /* measure update rate every 5 seconds */
- if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
- _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
- last_rate_measurement = hrt_absolute_time();
- last_rate_count = 0;
- _Helper->store_update_rates();
- _Helper->reset_update_rates();
+ last_rate_count++;
+
+ /* measure update rate every 5 seconds */
+ if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
+ _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
+ last_rate_measurement = hrt_absolute_time();
+ last_rate_count = 0;
+ _Helper->store_update_rates();
+ _Helper->reset_update_rates();
+ }
+
+ if (!_healthy) {
+ char *mode_str = "unknown";
+
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ mode_str = "UBX";
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ mode_str = "MTK";
+ break;
+
+ default:
+ break;
+ }
+
+ warnx("module found: %s", mode_str);
+ _healthy = true;
+ }
}
- if (!_healthy) {
- warnx("module found");
- _healthy = true;
+ if (_healthy) {
+ warnx("module lost");
+ _healthy = false;
+ _rate = 0.0f;
}
- }
- if (_healthy) {
- warnx("module lost");
- _healthy = false;
- _rate = 0.0f;
+
+ lock();
}
lock();
- }
- lock();
- /* select next mode */
- switch (_mode) {
+ /* select next mode */
+ switch (_mode) {
case GPS_DRIVER_MODE_UBX:
_mode = GPS_DRIVER_MODE_MTK;
break;
+
case GPS_DRIVER_MODE_MTK:
_mode = GPS_DRIVER_MODE_UBX;
break;
- // case GPS_DRIVER_MODE_NMEA:
- // _mode = GPS_DRIVER_MODE_UBX;
- // break;
+
default:
break;
+ }
}
}
- debug("exiting");
+
+ warnx("exiting");
::close(_serial_fd);
@@ -361,23 +423,25 @@ void
GPS::print_info()
{
switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- warnx("protocol: UBX");
- break;
- case GPS_DRIVER_MODE_MTK:
- warnx("protocol: MTK");
- break;
- case GPS_DRIVER_MODE_NMEA:
- warnx("protocol: NMEA");
- break;
- default:
- break;
+ case GPS_DRIVER_MODE_UBX:
+ warnx("protocol: UBX");
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ warnx("protocol: MTK");
+ break;
+
+ default:
+ break;
}
+
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
+
if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type,
- (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f));
+ warnx("position lock: %dD, satellites: %d, last update: %fms ago", (int)_report.fix_type,
+ _report.satellites_visible, (hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
+ warnx("eph: %.2fm, epv: %.2fm", _report.eph_m, _report.epv_m);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
@@ -395,7 +459,7 @@ namespace gps
GPS *g_dev;
-void start(const char *uart_path);
+void start(const char *uart_path, bool fake_gps);
void stop();
void test();
void reset();
@@ -405,7 +469,7 @@ void info();
* Start the driver.
*/
void
-start(const char *uart_path)
+start(const char *uart_path, bool fake_gps)
{
int fd;
@@ -413,7 +477,7 @@ start(const char *uart_path)
errx(1, "already started");
/* create the driver */
- g_dev = new GPS(uart_path);
+ g_dev = new GPS(uart_path, fake_gps);
if (g_dev == nullptr)
goto fail;
@@ -428,6 +492,7 @@ start(const char *uart_path)
errx(1, "Could not open device path: %s\n", GPS_DEVICE_PATH);
goto fail;
}
+
exit(0);
fail:
@@ -503,7 +568,8 @@ gps_main(int argc, char *argv[])
{
/* set to default */
- char* device_name = GPS_DEFAULT_UART_PORT;
+ char *device_name = GPS_DEFAULT_UART_PORT;
+ bool fake_gps = false;
/*
* Start/load the driver.
@@ -513,15 +579,24 @@ gps_main(int argc, char *argv[])
if (argc > 3) {
if (!strcmp(argv[2], "-d")) {
device_name = argv[3];
+
} else {
goto out;
}
}
- gps::start(device_name);
+
+ /* Detect fake gps option */
+ for (int i = 2; i < argc; i++) {
+ if (!strcmp(argv[i], "-f"))
+ fake_gps = true;
+ }
+
+ gps::start(device_name, fake_gps);
}
if (!strcmp(argv[1], "stop"))
gps::stop();
+
/*
* Test the driver/device.
*/
@@ -541,5 +616,5 @@ gps_main(int argc, char *argv[])
gps::info();
out:
- errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n]");
+ errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f]");
}
diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index ba86d370a..2360ff39b 100644
--- a/src/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012-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
@@ -41,6 +39,9 @@
/**
* @file gps_helper.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
float
@@ -87,13 +88,15 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud)
case 115200: speed = B115200; break;
- warnx("try baudrate: %d\n", speed);
+ warnx("try baudrate: %d\n", speed);
default:
warnx("ERROR: Unsupported baudrate: %d\n", baud);
return -EINVAL;
}
+
struct termios uart_config;
+
int termios_state;
/* fill the struct for the new configuration */
@@ -109,14 +112,17 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud)
warnx("ERROR setting config: %d (cfsetispeed)\n", termios_state);
return -1;
}
+
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
warnx("ERROR setting config: %d (cfsetospeed)\n", termios_state);
return -1;
}
+
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
warnx("ERROR setting baudrate (tcsetattr)\n");
return -1;
}
+
/* XXX if resetting the parser here, ensure it does exist (check for null pointer) */
return 0;
}
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index defc1a074..cfb9e0d43 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012-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
@@ -33,8 +31,10 @@
*
****************************************************************************/
-/**
+/**
* @file gps_helper.h
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef GPS_HELPER_H
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index 097db2abf..82c67d40a 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012-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
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 62941d74b..c90ecbe28 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012, 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
@@ -33,7 +31,12 @@
*
****************************************************************************/
-/* @file mkt.cpp */
+/**
+ * @file mtk.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
#include <unistd.h>
#include <stdio.h>
@@ -48,9 +51,9 @@
MTK::MTK(const int &fd, struct vehicle_gps_position_s *gps_position) :
-_fd(fd),
-_gps_position(gps_position),
-_mtk_revision(0)
+ _fd(fd),
+ _gps_position(gps_position),
+ _mtk_revision(0)
{
decode_init();
}
@@ -73,24 +76,28 @@ MTK::configure(unsigned &baudrate)
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(MTK_SET_BINARY) != write(_fd, MTK_SET_BINARY, strlen(MTK_SET_BINARY))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(SBAS_ON) != write(_fd, SBAS_ON, strlen(SBAS_ON))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(WAAS_ON) != write(_fd, WAAS_ON, strlen(WAAS_ON))) {
warnx("mtk: config write failed");
return -1;
}
+
usleep(10000);
if (strlen(MTK_NAVTHRES_OFF) != write(_fd, MTK_NAVTHRES_OFF, strlen(MTK_NAVTHRES_OFF))) {
@@ -128,12 +135,15 @@ MTK::receive(unsigned timeout)
handle_message(packet);
return 1;
}
+
/* in case we keep trying but only get crap from GPS */
- if (time_started + timeout*1000 < hrt_absolute_time() ) {
+ if (time_started + timeout * 1000 < hrt_absolute_time()) {
return -1;
}
+
j++;
}
+
/* everything is read */
j = count = 0;
}
@@ -181,6 +191,7 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
if (b == MTK_SYNC1_V16) {
_decode_state = MTK_DECODE_GOT_CK_A;
_mtk_revision = 16;
+
} else if (b == MTK_SYNC1_V19) {
_decode_state = MTK_DECODE_GOT_CK_A;
_mtk_revision = 19;
@@ -201,7 +212,7 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
add_byte_to_checksum(b);
// Fill packet buffer
- ((uint8_t*)(&packet))[_rx_count] = b;
+ ((uint8_t *)(&packet))[_rx_count] = b;
_rx_count++;
/* Packet size minus checksum, XXX ? */
@@ -209,14 +220,17 @@ MTK::parse_char(uint8_t b, gps_mtk_packet_t &packet)
/* Compare checksum */
if (_rx_ck_a == packet.ck_a && _rx_ck_b == packet.ck_b) {
ret = 1;
+
} else {
warnx("MTK Checksum invalid");
ret = -1;
}
+
// Reset state machine to decode next packet
decode_init();
}
}
+
return ret;
}
@@ -226,19 +240,22 @@ MTK::handle_message(gps_mtk_packet_t &packet)
if (_mtk_revision == 16) {
_gps_position->lat = packet.latitude * 10; // from degrees*1e6 to degrees*1e7
_gps_position->lon = packet.longitude * 10; // from degrees*1e6 to degrees*1e7
+
} else if (_mtk_revision == 19) {
_gps_position->lat = packet.latitude; // both degrees*1e7
_gps_position->lon = packet.longitude; // both degrees*1e7
+
} else {
warnx("mtk: unknown revision");
_gps_position->lat = 0;
_gps_position->lon = 0;
}
+
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
_gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
_gps_position->epv_m = 0.0; //unknown in mtk custom mode
- _gps_position->vel_m_s = ((float)packet.ground_speed)*1e-2f; // from cm/s to m/s
+ _gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
_gps_position->satellites_visible = packet.satellites;
diff --git a/src/drivers/gps/mtk.h b/src/drivers/gps/mtk.h
index b5cfbf0a6..a2d5e27bb 100644
--- a/src/drivers/gps/mtk.h
+++ b/src/drivers/gps/mtk.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012, 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
@@ -33,7 +31,12 @@
*
****************************************************************************/
-/* @file mtk.h */
+/**
+ * @file mtk.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
#ifndef MTK_H_
#define MTK_H_
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index b3093b0f6..8a2afecb7 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012, 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
@@ -39,15 +37,21 @@
* U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
* including Prototol Specification.
*
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
*/
-#include <unistd.h>
-#include <stdio.h>
-#include <poll.h>
+#include <assert.h>
#include <math.h>
+#include <poll.h>
+#include <stdio.h>
#include <string.h>
-#include <assert.h>
+#include <time.h>
+#include <unistd.h>
+
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
@@ -55,13 +59,17 @@
#include "ubx.h"
-#define UBX_CONFIG_TIMEOUT 100
+#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
+#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
+#define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls
+#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
-_fd(fd),
-_gps_position(gps_position),
-_waiting_for_ack(false),
-_disable_cmd_counter(0)
+ _fd(fd),
+ _gps_position(gps_position),
+ _configured(false),
+ _waiting_for_ack(false),
+ _disable_cmd_last(0)
{
decode_init();
}
@@ -73,12 +81,13 @@ UBX::~UBX()
int
UBX::configure(unsigned &baudrate)
{
- _waiting_for_ack = true;
-
+ _configured = false;
/* try different baudrates */
const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
- for (int baud_i = 0; baud_i < 5; baud_i++) {
+ int baud_i;
+
+ for (baud_i = 0; baud_i < 5; baud_i++) {
baudrate = baudrates_to_try[baud_i];
set_baudrate(_fd, baudrate);
@@ -89,8 +98,8 @@ UBX::configure(unsigned &baudrate)
/* Set everything else of the packet to 0, otherwise the module wont accept it */
memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet));
- _clsID_needed = UBX_CLASS_CFG;
- _msgID_needed = UBX_MESSAGE_CFG_PRT;
+ _message_class_needed = UBX_CLASS_CFG;
+ _message_id_needed = UBX_MESSAGE_CFG_PRT;
/* Define the package contents, don't change the baudrate */
cfg_prt_packet.clsID = UBX_CLASS_CFG;
@@ -102,9 +111,9 @@ UBX::configure(unsigned &baudrate)
cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
- send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
+ send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
- if (receive(UBX_CONFIG_TIMEOUT) < 0) {
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
/* try next baudrate */
continue;
}
@@ -120,100 +129,125 @@ UBX::configure(unsigned &baudrate)
cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
- send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
-
+ send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
+
/* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
- receive(UBX_CONFIG_TIMEOUT);
-
+ wait_for_ack(UBX_CONFIG_TIMEOUT);
+
if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
}
- /* send a CFT-RATE message to define update rate */
- type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
- memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
+ /* at this point we have correct baudrate on both ends */
+ break;
+ }
- _clsID_needed = UBX_CLASS_CFG;
- _msgID_needed = UBX_MESSAGE_CFG_RATE;
+ if (baud_i >= 5) {
+ return 1;
+ }
- cfg_rate_packet.clsID = UBX_CLASS_CFG;
- cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
- cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
- cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL;
- cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
- cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
+ /* send a CFG-RATE message to define update rate */
+ type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
+ memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
- send_config_packet(_fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet));
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- /* try next baudrate */
- continue;
- }
+ _message_class_needed = UBX_CLASS_CFG;
+ _message_id_needed = UBX_MESSAGE_CFG_RATE;
- /* send a NAV5 message to set the options for the internal filter */
- type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
- memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
+ cfg_rate_packet.clsID = UBX_CLASS_CFG;
+ cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
+ cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
+ cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL;
+ cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
+ cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
- _clsID_needed = UBX_CLASS_CFG;
- _msgID_needed = UBX_MESSAGE_CFG_NAV5;
+ send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
- cfg_nav5_packet.clsID = UBX_CLASS_CFG;
- cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
- cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
- cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
- cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
- cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: configuration failed: RATE");
+ return 1;
+ }
- send_config_packet(_fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- /* try next baudrate */
- continue;
- }
+ /* send a NAV5 message to set the options for the internal filter */
+ type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
+ memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
+
+ _message_class_needed = UBX_CLASS_CFG;
+ _message_id_needed = UBX_MESSAGE_CFG_NAV5;
+
+ cfg_nav5_packet.clsID = UBX_CLASS_CFG;
+ cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
+ cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
+ cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
+ cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
+ cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
+
+ send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: configuration failed: NAV5");
+ return 1;
+ }
+
+ /* configure message rates */
+ /* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */
+ configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: msg rate configuration failed: NAV POSLLH");
+ return 1;
+ }
+
+ configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: msg rate configuration failed: NAV TIMEUTC");
+ return 1;
+ }
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH,
- UBX_CFG_MSG_PAYLOAD_RATE1_5HZ);
- /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC,
- 1);
- // /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL,
- 1);
- // /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED,
- 1);
- // /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
- // configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_DOP,
- // 0);
- // /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO,
- 0);
- // /* insist of receiving the ACK for this packet */
- // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0)
- // continue;
-
- _waiting_for_ack = false;
- return 0;
+ configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: msg rate configuration failed: NAV SOL");
+ return 1;
+ }
+
+ configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: msg rate configuration failed: NAV VELNED");
+ return 1;
+ }
+
+ configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("ubx: msg rate configuration failed: NAV SVINFO");
+ return 1;
}
- return -1;
+
+ _configured = true;
+ return 0;
}
int
UBX::wait_for_ack(unsigned timeout)
{
_waiting_for_ack = true;
- int ret = receive(timeout);
- _waiting_for_ack = false;
- return ret;
+ uint64_t time_started = hrt_absolute_time();
+
+ while (hrt_absolute_time() < time_started + timeout * 1000) {
+ if (receive(timeout) > 0) {
+ if (!_waiting_for_ack) {
+ return 1;
+ }
+
+ } else {
+ return -1; // timeout or error receiving, or NAK
+ }
+ }
+
+ return -1; // timeout
}
int
@@ -224,56 +258,61 @@ UBX::receive(unsigned timeout)
fds[0].fd = _fd;
fds[0].events = POLLIN;
- uint8_t buf[32];
+ uint8_t buf[128];
/* timeout additional to poll */
uint64_t time_started = hrt_absolute_time();
- int j = 0;
ssize_t count = 0;
- while (true) {
+ bool handled = false;
- /* pass received bytes to the packet decoder */
- while (j < count) {
- if (parse_char(buf[j]) > 0) {
- /* return to configure during configuration or to the gps driver during normal work
- * if a packet has arrived */
- if (handle_message() > 0)
- return 1;
- }
- /* in case we keep trying but only get crap from GPS */
- if (time_started + timeout*1000 < hrt_absolute_time() ) {
- return -1;
- }
- j++;
- }
-
- /* everything is read */
- j = count = 0;
+ while (true) {
- /* then poll for new data */
- int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout);
+ /* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */
+ int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), handled ? UBX_PACKET_TIMEOUT : timeout);
if (ret < 0) {
/* something went wrong when polling */
+ warnx("ubx: poll error");
return -1;
} else if (ret == 0) {
- /* Timeout */
- return -1;
+ /* return success after short delay after receiving a packet or timeout after long delay */
+ if (handled) {
+ return 1;
+
+ } else {
+ return -1;
+ }
} else if (ret > 0) {
/* if we have new data from GPS, go handle it */
if (fds[0].revents & POLLIN) {
/*
* We are here because poll says there is some data, so this
- * won't block even on a blocking device. If more bytes are
- * available, we'll go back to poll() again...
+ * won't block even on a blocking device. But don't read immediately
+ * by 1-2 bytes, wait for some more data to save expensive read() calls.
+ * If more bytes are available, we'll go back to poll() again.
*/
- count = ::read(_fd, buf, sizeof(buf));
+ usleep(UBX_WAIT_BEFORE_READ * 1000);
+ count = read(_fd, buf, sizeof(buf));
+
+ /* pass received bytes to the packet decoder */
+ for (int i = 0; i < count; i++) {
+ if (parse_char(buf[i]) > 0) {
+ if (handle_message() > 0)
+ handled = true;
+ }
+ }
}
}
+
+ /* abort after timeout if no useful packets received */
+ if (time_started + timeout * 1000 < hrt_absolute_time()) {
+ warnx("ubx: timeout - no useful messages");
+ return -1;
+ }
}
}
@@ -282,410 +321,304 @@ UBX::parse_char(uint8_t b)
{
switch (_decode_state) {
/* First, look for sync1 */
- case UBX_DECODE_UNINIT:
- if (b == UBX_SYNC1) {
- _decode_state = UBX_DECODE_GOT_SYNC1;
- }
- break;
- /* Second, look for sync2 */
- case UBX_DECODE_GOT_SYNC1:
- if (b == UBX_SYNC2) {
- _decode_state = UBX_DECODE_GOT_SYNC2;
- } else {
- /* Second start symbol was wrong, reset state machine */
- decode_init();
- }
- break;
- /* Now look for class */
- case UBX_DECODE_GOT_SYNC2:
- /* everything except sync1 and sync2 needs to be added to the checksum */
- add_byte_to_checksum(b);
- /* check for known class */
- switch (b) {
- case UBX_CLASS_ACK:
- _decode_state = UBX_DECODE_GOT_CLASS;
- _message_class = ACK;
- break;
+ case UBX_DECODE_UNINIT:
+ if (b == UBX_SYNC1) {
+ _decode_state = UBX_DECODE_GOT_SYNC1;
+ }
- case UBX_CLASS_NAV:
- _decode_state = UBX_DECODE_GOT_CLASS;
- _message_class = NAV;
- break;
+ break;
-// case UBX_CLASS_RXM:
-// _decode_state = UBX_DECODE_GOT_CLASS;
-// _message_class = RXM;
-// break;
+ /* Second, look for sync2 */
+ case UBX_DECODE_GOT_SYNC1:
+ if (b == UBX_SYNC2) {
+ _decode_state = UBX_DECODE_GOT_SYNC2;
+
+ } else {
+ /* Second start symbol was wrong, reset state machine */
+ decode_init();
+ /* don't return error, it can be just false sync1 */
+ }
- case UBX_CLASS_CFG:
- _decode_state = UBX_DECODE_GOT_CLASS;
- _message_class = CFG;
- break;
- default: //unknown class: reset state machine
- decode_init();
- break;
- }
- break;
- case UBX_DECODE_GOT_CLASS:
- add_byte_to_checksum(b);
- switch (_message_class) {
- case NAV:
- switch (b) {
- case UBX_MESSAGE_NAV_POSLLH:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = NAV_POSLLH;
- break;
-
- case UBX_MESSAGE_NAV_SOL:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = NAV_SOL;
- break;
-
- case UBX_MESSAGE_NAV_TIMEUTC:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = NAV_TIMEUTC;
- break;
-
-// case UBX_MESSAGE_NAV_DOP:
-// _decode_state = UBX_DECODE_GOT_MESSAGEID;
-// _message_id = NAV_DOP;
-// break;
-
- case UBX_MESSAGE_NAV_SVINFO:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = NAV_SVINFO;
- break;
-
- case UBX_MESSAGE_NAV_VELNED:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = NAV_VELNED;
- break;
-
- default: //unknown class: reset state machine, should not happen
- decode_init();
- break;
- }
- break;
-// case RXM:
-// switch (b) {
-// case UBX_MESSAGE_RXM_SVSI:
-// _decode_state = UBX_DECODE_GOT_MESSAGEID;
-// _message_id = RXM_SVSI;
-// break;
-//
-// default: //unknown class: reset state machine, should not happen
-// decode_init();
-// break;
-// }
-// break;
-
- case CFG:
- switch (b) {
- case UBX_MESSAGE_CFG_NAV5:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = CFG_NAV5;
- break;
-
- default: //unknown class: reset state machine, should not happen
- decode_init();
- break;
- }
- break;
+ break;
- case ACK:
- switch (b) {
- case UBX_MESSAGE_ACK_ACK:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = ACK_ACK;
- break;
- case UBX_MESSAGE_ACK_NAK:
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
- _message_id = ACK_NAK;
- break;
- default: //unknown class: reset state machine, should not happen
- decode_init();
- break;
- }
- break;
- default: //should not happen because we set the class
- warnx("UBX Error, we set a class that we don't know");
- decode_init();
-// config_needed = true;
- break;
- }
- break;
- case UBX_DECODE_GOT_MESSAGEID:
- add_byte_to_checksum(b);
- _payload_size = b; //this is the first length byte
- _decode_state = UBX_DECODE_GOT_LENGTH1;
- break;
- case UBX_DECODE_GOT_LENGTH1:
- add_byte_to_checksum(b);
- _payload_size += b << 8; // here comes the second byte of length
- _decode_state = UBX_DECODE_GOT_LENGTH2;
- break;
- case UBX_DECODE_GOT_LENGTH2:
- /* Add to checksum if not yet at checksum byte */
- if (_rx_count < _payload_size)
- add_byte_to_checksum(b);
- _rx_buffer[_rx_count] = b;
- /* once the payload has arrived, we can process the information */
- if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
-
- /* compare checksum */
- if (_rx_ck_a == _rx_buffer[_rx_count-1] && _rx_ck_b == _rx_buffer[_rx_count]) {
- return 1;
- } else {
- decode_init();
- return -1;
- warnx("ubx: Checksum wrong");
- }
+ /* Now look for class */
+ case UBX_DECODE_GOT_SYNC2:
+ /* everything except sync1 and sync2 needs to be added to the checksum */
+ add_byte_to_checksum(b);
+ _message_class = b;
+ _decode_state = UBX_DECODE_GOT_CLASS;
+ break;
- return 1;
- } else if (_rx_count < RECV_BUFFER_SIZE) {
- _rx_count++;
- } else {
- warnx("ubx: buffer full");
- decode_init();
- return -1;
- }
- break;
- default:
- break;
- }
- return 0; //XXX ?
-}
+ case UBX_DECODE_GOT_CLASS:
+ add_byte_to_checksum(b);
+ _message_id = b;
+ _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ break;
+ case UBX_DECODE_GOT_MESSAGEID:
+ add_byte_to_checksum(b);
+ _payload_size = b; //this is the first length byte
+ _decode_state = UBX_DECODE_GOT_LENGTH1;
+ break;
-int
-UBX::handle_message()
-{
- int ret = 0;
+ case UBX_DECODE_GOT_LENGTH1:
+ add_byte_to_checksum(b);
+ _payload_size += b << 8; // here comes the second byte of length
+ _decode_state = UBX_DECODE_GOT_LENGTH2;
+ break;
- switch (_message_id) { //this enum is unique for all ids --> no need to check the class
- case NAV_POSLLH: {
-// printf("GOT NAV_POSLLH MESSAGE\n");
- if (!_waiting_for_ack) {
- gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
+ case UBX_DECODE_GOT_LENGTH2:
- _gps_position->lat = packet->lat;
- _gps_position->lon = packet->lon;
- _gps_position->alt = packet->height_msl;
+ /* Add to checksum if not yet at checksum byte */
+ if (_rx_count < _payload_size)
+ add_byte_to_checksum(b);
- _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
- _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
+ _rx_buffer[_rx_count] = b;
- _rate_count_lat_lon++;
+ /* once the payload has arrived, we can process the information */
+ if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
+ /* compare checksum */
+ if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) {
+ decode_init();
+ return 1; // message received successfully
- /* Add timestamp to finish the report */
- _gps_position->timestamp_position = hrt_absolute_time();
- /* only return 1 when new position is available */
- ret = 1;
+ } else {
+ warnx("ubx: checksum wrong");
+ decode_init();
+ return -1;
}
- break;
+
+ } else if (_rx_count < RECV_BUFFER_SIZE) {
+ _rx_count++;
+
+ } else {
+ warnx("ubx: buffer full");
+ decode_init();
+ return -1;
}
- case NAV_SOL: {
-// printf("GOT NAV_SOL MESSAGE\n");
- if (!_waiting_for_ack) {
- gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
+ break;
- _gps_position->fix_type = packet->gpsFix;
- _gps_position->s_variance_m_s = packet->sAcc;
- _gps_position->p_variance_m = packet->pAcc;
+ default:
+ break;
+ }
- _gps_position->timestamp_variance = hrt_absolute_time();
- }
- break;
- }
+ return 0; // message decoding in progress
+}
-// case NAV_DOP: {
-//// printf("GOT NAV_DOP MESSAGE\n");
-// gps_bin_nav_dop_packet_t *packet = (gps_bin_nav_dop_packet_t *) _rx_buffer;
-//
-// _gps_position->eph_m = packet->hDOP;
-// _gps_position->epv = packet->vDOP;
-//
-// _gps_position->timestamp_posdilution = hrt_absolute_time();
-//
-// _new_nav_dop = true;
-//
-// break;
-// }
-
- case NAV_TIMEUTC: {
-// printf("GOT NAV_TIMEUTC MESSAGE\n");
- if (!_waiting_for_ack) {
- gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
- //convert to unix timestamp
- struct tm timeinfo;
- timeinfo.tm_year = packet->year - 1900;
- timeinfo.tm_mon = packet->month - 1;
- timeinfo.tm_mday = packet->day;
- timeinfo.tm_hour = packet->hour;
- timeinfo.tm_min = packet->min;
- timeinfo.tm_sec = packet->sec;
+int
+UBX::handle_message()
+{
+ int ret = 0;
- time_t epoch = mktime(&timeinfo);
+ if (_configured) {
+ /* handle only info messages when configured */
+ switch (_message_class) {
+ case UBX_CLASS_NAV:
+ switch (_message_id) {
+ case UBX_MESSAGE_NAV_POSLLH: {
+ // printf("GOT NAV_POSLLH\n");
+ gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
- _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
- _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
+ _gps_position->lat = packet->lat;
+ _gps_position->lon = packet->lon;
+ _gps_position->alt = packet->height_msl;
+ _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
+ _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
+ _gps_position->timestamp_position = hrt_absolute_time();
- _gps_position->timestamp_time = hrt_absolute_time();
- }
- break;
- }
+ _rate_count_lat_lon++;
- case NAV_SVINFO: {
-// printf("GOT NAV_SVINFO MESSAGE\n");
+ ret = 1;
+ break;
+ }
- if (!_waiting_for_ack) {
- //this is a more complicated message: the length depends on the number of satellites. This number is extracted from the first part of the message
- const int length_part1 = 8;
- char _rx_buffer_part1[length_part1];
- memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
- gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer_part1;
+ case UBX_MESSAGE_NAV_SOL: {
+ // printf("GOT NAV_SOL\n");
+ gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
- //read checksum
- const int length_part3 = 2;
- char _rx_buffer_part3[length_part3];
- memcpy(_rx_buffer_part3, &(_rx_buffer[_rx_count - 1]), length_part3);
+ _gps_position->fix_type = packet->gpsFix;
+ _gps_position->s_variance_m_s = packet->sAcc;
+ _gps_position->p_variance_m = packet->pAcc;
+ _gps_position->timestamp_variance = hrt_absolute_time();
- //definitions needed to read numCh elements from the buffer:
- const int length_part2 = 12;
- gps_bin_nav_svinfo_part2_packet_t *packet_part2;
- char _rx_buffer_part2[length_part2]; //for temporal storage
+ ret = 1;
+ break;
+ }
- uint8_t satellites_used = 0;
- int i;
+ case UBX_MESSAGE_NAV_TIMEUTC: {
+ // printf("GOT NAV_TIMEUTC\n");
+ gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
+
+ /* convert to unix timestamp */
+ struct tm timeinfo;
+ timeinfo.tm_year = packet->year - 1900;
+ timeinfo.tm_mon = packet->month - 1;
+ timeinfo.tm_mday = packet->day;
+ timeinfo.tm_hour = packet->hour;
+ timeinfo.tm_min = packet->min;
+ timeinfo.tm_sec = packet->sec;
+ time_t epoch = mktime(&timeinfo);
+
+#ifndef CONFIG_RTC
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = packet->time_nanoseconds;
+ clock_settime(CLOCK_REALTIME, &ts);
+#endif
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
+ _gps_position->timestamp_time = hrt_absolute_time();
- for (i = 0; i < packet_part1->numCh; i++) { //for each channel
+ ret = 1;
+ break;
+ }
- /* Get satellite information from the buffer */
- memcpy(_rx_buffer_part2, &(_rx_buffer[length_part1 + i * length_part2]), length_part2);
- packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) _rx_buffer_part2;
+ case UBX_MESSAGE_NAV_SVINFO: {
+ //printf("GOT NAV_SVINFO\n");
+ const int length_part1 = 8;
+ gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer;
+ const int length_part2 = 12;
+ gps_bin_nav_svinfo_part2_packet_t *packet_part2;
+ uint8_t satellites_used = 0;
+ int i;
- /* Write satellite information in the global storage */
- _gps_position->satellite_prn[i] = packet_part2->svid;
+ //printf("Number of Channels: %d\n", packet_part1->numCh);
+ for (i = 0; i < packet_part1->numCh; i++) {
+ /* set pointer to sattelite_i information */
+ packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + i * length_part2]);
- //if satellite information is healthy store the data
- uint8_t unhealthy = packet_part2->flags & 1 << 4; //flags is a bitfield
+ /* write satellite information to global storage */
+ uint8_t sv_used = packet_part2->flags & 0x01;
- if (!unhealthy) {
- if ((packet_part2->flags) & 1) { //flags is a bitfield
- _gps_position->satellite_used[i] = 1;
+ if (sv_used) {
+ /* count SVs used for NAV */
satellites_used++;
-
- } else {
- _gps_position->satellite_used[i] = 0;
}
+ /* record info for all channels, whether or not the SV is used for NAV */
+ _gps_position->satellite_used[i] = sv_used;
_gps_position->satellite_snr[i] = packet_part2->cno;
_gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
_gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
+ _gps_position->satellite_prn[i] = packet_part2->svid;
+ //printf("SAT %d: %d %d %d %d\n", i, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid);
+ }
- } else {
+ for (i = packet_part1->numCh; i < 20; i++) {
+ /* unused channels have to be set to zero for e.g. MAVLink */
+ _gps_position->satellite_prn[i] = 0;
_gps_position->satellite_used[i] = 0;
_gps_position->satellite_snr[i] = 0;
_gps_position->satellite_elevation[i] = 0;
_gps_position->satellite_azimuth[i] = 0;
}
- }
+ _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
+
+ if (packet_part1->numCh > 0) {
+ _gps_position->satellite_info_available = true;
+
+ } else {
+ _gps_position->satellite_info_available = false;
+ }
+
+ _gps_position->timestamp_satellites = hrt_absolute_time();
- for (i = packet_part1->numCh; i < 20; i++) { //these channels are unused
- /* Unused channels have to be set to zero for e.g. MAVLink */
- _gps_position->satellite_prn[i] = 0;
- _gps_position->satellite_used[i] = 0;
- _gps_position->satellite_snr[i] = 0;
- _gps_position->satellite_elevation[i] = 0;
- _gps_position->satellite_azimuth[i] = 0;
+ ret = 1;
+ break;
}
- _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
- /* set timestamp if any sat info is available */
- if (packet_part1->numCh > 0) {
- _gps_position->satellite_info_available = true;
- } else {
- _gps_position->satellite_info_available = false;
+ case UBX_MESSAGE_NAV_VELNED: {
+ // printf("GOT NAV_VELNED\n");
+ gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
+
+ _gps_position->vel_m_s = (float)packet->speed * 1e-2f;
+ _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
+ _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
+ _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
+ _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->vel_ned_valid = true;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+
+ _rate_count_vel++;
+
+ ret = 1;
+ break;
}
- _gps_position->timestamp_satellites = hrt_absolute_time();
+
+ default:
+ break;
}
break;
- }
- case NAV_VELNED: {
-
- if (!_waiting_for_ack) {
- /* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */
- gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
-
- _gps_position->vel_m_s = (float)packet->speed * 1e-2f;
- _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
- _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
- _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
- _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->vel_ned_valid = true;
- _gps_position->timestamp_velocity = hrt_absolute_time();
-
- _rate_count_vel++;
+ case UBX_CLASS_ACK: {
+ /* ignore ACK when already configured */
+ ret = 1;
+ break;
}
+ default:
break;
}
-// case RXM_SVSI: {
-// printf("GOT RXM_SVSI MESSAGE\n");
-// const int length_part1 = 7;
-// char _rx_buffer_part1[length_part1];
-// memcpy(_rx_buffer_part1, _rx_buffer, length_part1);
-// gps_bin_rxm_svsi_packet_t *packet = (gps_bin_rxm_svsi_packet_t *) _rx_buffer_part1;
-//
-// _gps_position->satellites_visible = packet->numVis;
-// _gps_position->counter++;
-// _last_message_timestamps[RXM_SVSI - 1] = hrt_absolute_time();
-//
-// break;
-// }
- case ACK_ACK: {
-// printf("GOT ACK_ACK\n");
- gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
-
- if (_waiting_for_ack) {
- if (packet->clsID == _clsID_needed && packet->msgID == _msgID_needed) {
- ret = 1;
- }
+ if (ret == 0) {
+ /* message not handled */
+ warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
+
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
+ /* don't attempt for every message to disable, some might not be disabled */
+ _disable_cmd_last = t;
+ warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
+ configure_message_rate(_message_class, _message_id, 0);
}
}
- break;
- case ACK_NAK: {
-// printf("GOT ACK_NAK\n");
- warnx("UBX: Received: Not Acknowledged");
- /* configuration obviously not successful */
- ret = -1;
- break;
- }
+ } else {
+ /* handle only ACK while configuring */
+ if (_message_class == UBX_CLASS_ACK) {
+ switch (_message_id) {
+ case UBX_MESSAGE_ACK_ACK: {
+ // printf("GOT ACK_ACK\n");
+ gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
+
+ if (_waiting_for_ack) {
+ if (packet->clsID == _message_class_needed && packet->msgID == _message_id_needed) {
+ _waiting_for_ack = false;
+ ret = 1;
+ }
+ }
- default: //we don't know the message
- warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id);
- if (_disable_cmd_counter++ == 0) {
- // Don't attempt for every message to disable, some might not be disabled */
- warnx("Disabling message 0x%02x 0x%02x", (unsigned)_message_class, (unsigned)_message_id);
- configure_message_rate(_message_class, _message_id, 0);
+ break;
+ }
+
+ case UBX_MESSAGE_ACK_NAK: {
+ // printf("GOT ACK_NAK\n");
+ warnx("ubx: not acknowledged");
+ /* configuration obviously not successful */
+ _waiting_for_ack = false;
+ ret = -1;
+ break;
+ }
+
+ default:
+ break;
}
- return ret;
- ret = -1;
- break;
}
- // end if _rx_count high enough
+ }
+
decode_init();
- return ret; //XXX?
+ return ret;
}
void
@@ -695,9 +628,8 @@ UBX::decode_init(void)
_rx_ck_b = 0;
_rx_count = 0;
_decode_state = UBX_DECODE_UNINIT;
- _message_class = CLASS_UNKNOWN;
- _message_id = ID_UNKNOWN;
_payload_size = 0;
+ /* don't reset _message_class, _message_id, _rx_buffer leave it for message handler */
}
void
@@ -708,23 +640,24 @@ UBX::add_byte_to_checksum(uint8_t b)
}
void
-UBX::add_checksum_to_message(uint8_t* message, const unsigned length)
+UBX::add_checksum_to_message(uint8_t *message, const unsigned length)
{
uint8_t ck_a = 0;
uint8_t ck_b = 0;
unsigned i;
- for (i = 0; i < length-2; i++) {
+ for (i = 0; i < length - 2; i++) {
ck_a = ck_a + message[i];
ck_b = ck_b + ck_a;
}
- /* The checksum is written to the last to bytes of a message */
- message[length-2] = ck_a;
- message[length-1] = ck_b;
+
+ /* the checksum is written to the last to bytes of a message */
+ message[length - 2] = ck_a;
+ message[length - 1] = ck_b;
}
void
-UBX::add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b)
+UBX::add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b)
{
for (unsigned i = 0; i < length; i++) {
ck_a = ck_a + message[i];
@@ -735,11 +668,11 @@ UBX::add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_
void
UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
{
- struct ubx_cfg_msg_rate msg;
- msg.msg_class = msg_class;
- msg.msg_id = msg_id;
- msg.rate = rate;
- send_message(CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
+ struct ubx_cfg_msg_rate msg;
+ msg.msg_class = msg_class;
+ msg.msg_id = msg_id;
+ msg.rate = rate;
+ send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
}
void
@@ -747,36 +680,36 @@ UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
{
ssize_t ret = 0;
- /* Calculate the checksum now */
+ /* calculate the checksum now */
add_checksum_to_message(packet, length);
const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
- /* Start with the two sync bytes */
+ /* start with the two sync bytes */
ret += write(fd, sync_bytes, sizeof(sync_bytes));
ret += write(fd, packet, length);
if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
- warnx("ubx: config write fail");
+ warnx("ubx: configuration write fail");
}
void
UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size)
{
struct ubx_header header;
- uint8_t ck_a=0, ck_b=0;
+ uint8_t ck_a = 0, ck_b = 0;
header.sync1 = UBX_SYNC1;
header.sync2 = UBX_SYNC2;
header.msg_class = msg_class;
header.msg_id = msg_id;
header.length = size;
- add_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b);
+ add_checksum((uint8_t *)&header.msg_class, sizeof(header) - 2, ck_a, ck_b);
add_checksum((uint8_t *)msg, size, ck_a, ck_b);
- // Configure receive check
- _clsID_needed = msg_class;
- _msgID_needed = msg_id;
+ /* configure ACK check */
+ _message_class_needed = msg_class;
+ _message_id_needed = msg_id;
write(_fd, (const char *)&header, sizeof(header));
write(_fd, (const char *)msg, size);
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 5a433642c..79a904f4a 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012, 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
@@ -33,7 +31,17 @@
*
****************************************************************************/
-/* @file U-Blox protocol definitions */
+/**
+ * @file ubx.h
+ *
+ * U-Blox protocol definition. Following u-blox 6/7 Receiver Description
+ * including Prototol Specification.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
+ */
#ifndef UBX_H_
#define UBX_H_
@@ -51,23 +59,23 @@
/* MessageIDs (the ones that are used) */
#define UBX_MESSAGE_NAV_POSLLH 0x02
-#define UBX_MESSAGE_NAV_SOL 0x06
-#define UBX_MESSAGE_NAV_TIMEUTC 0x21
//#define UBX_MESSAGE_NAV_DOP 0x04
-#define UBX_MESSAGE_NAV_SVINFO 0x30
+#define UBX_MESSAGE_NAV_SOL 0x06
#define UBX_MESSAGE_NAV_VELNED 0x12
//#define UBX_MESSAGE_RXM_SVSI 0x20
-#define UBX_MESSAGE_ACK_ACK 0x01
+#define UBX_MESSAGE_NAV_TIMEUTC 0x21
+#define UBX_MESSAGE_NAV_SVINFO 0x30
#define UBX_MESSAGE_ACK_NAK 0x00
+#define UBX_MESSAGE_ACK_ACK 0x01
#define UBX_MESSAGE_CFG_PRT 0x00
-#define UBX_MESSAGE_CFG_NAV5 0x24
#define UBX_MESSAGE_CFG_MSG 0x01
#define UBX_MESSAGE_CFG_RATE 0x08
+#define UBX_MESSAGE_CFG_NAV5 0x24
#define UBX_CFG_PRT_LENGTH 20
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
-#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */
+#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
@@ -299,44 +307,6 @@ struct ubx_cfg_msg_rate {
// ************
typedef enum {
- UBX_CONFIG_STATE_PRT = 0,
- UBX_CONFIG_STATE_PRT_NEW_BAUDRATE,
- UBX_CONFIG_STATE_RATE,
- UBX_CONFIG_STATE_NAV5,
- UBX_CONFIG_STATE_MSG_NAV_POSLLH,
- UBX_CONFIG_STATE_MSG_NAV_TIMEUTC,
- UBX_CONFIG_STATE_MSG_NAV_DOP,
- UBX_CONFIG_STATE_MSG_NAV_SVINFO,
- UBX_CONFIG_STATE_MSG_NAV_SOL,
- UBX_CONFIG_STATE_MSG_NAV_VELNED,
-// UBX_CONFIG_STATE_MSG_RXM_SVSI,
- UBX_CONFIG_STATE_CONFIGURED
-} ubx_config_state_t;
-
-typedef enum {
- CLASS_UNKNOWN = 0,
- NAV = 1,
- RXM = 2,
- ACK = 3,
- CFG = 4
-} ubx_message_class_t;
-
-typedef enum {
- //these numbers do NOT correspond to the message id numbers of the ubx protocol
- ID_UNKNOWN = 0,
- NAV_POSLLH,
- NAV_SOL,
- NAV_TIMEUTC,
-// NAV_DOP,
- NAV_SVINFO,
- NAV_VELNED,
-// RXM_SVSI,
- CFG_NAV5,
- ACK_ACK,
- ACK_NAK,
-} ubx_message_id_t;
-
-typedef enum {
UBX_DECODE_UNINIT = 0,
UBX_DECODE_GOT_SYNC1,
UBX_DECODE_GOT_SYNC2,
@@ -384,7 +354,7 @@ private:
/**
* Add the two checksum bytes to an outgoing message
*/
- void add_checksum_to_message(uint8_t* message, const unsigned length);
+ void add_checksum_to_message(uint8_t *message, const unsigned length);
/**
* Helper to send a config packet
@@ -395,25 +365,25 @@ private:
void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
- void add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
+ void add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
int wait_for_ack(unsigned timeout);
int _fd;
struct vehicle_gps_position_s *_gps_position;
- ubx_config_state_t _config_state;
+ bool _configured;
bool _waiting_for_ack;
- uint8_t _clsID_needed;
- uint8_t _msgID_needed;
+ uint8_t _message_class_needed;
+ uint8_t _message_id_needed;
ubx_decode_state_t _decode_state;
uint8_t _rx_buffer[RECV_BUFFER_SIZE];
unsigned _rx_count;
uint8_t _rx_ck_a;
uint8_t _rx_ck_b;
- ubx_message_class_t _message_class;
- ubx_message_id_t _message_id;
+ uint8_t _message_class;
+ uint8_t _message_id;
unsigned _payload_size;
- uint8_t _disable_cmd_counter;
+ uint8_t _disable_cmd_last;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index bd027ce0b..0a047f38f 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -75,6 +75,7 @@
#include <systemlib/mixer/mixer.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/actuator_outputs.h>
#include <systemlib/err.h>
@@ -192,9 +193,10 @@ HIL::~HIL()
} while (_task != -1);
}
- /* clean up the alternate device node */
- if (_primary_pwm_device)
- unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+ // XXX already claimed with CDEV
+ // /* clean up the alternate device node */
+ // if (_primary_pwm_device)
+ // unregister_driver(PWM_OUTPUT_DEVICE_PATH);
g_hil = nullptr;
}
@@ -403,7 +405,7 @@ HIL::task_main()
for (unsigned i = 0; i < num_outputs; i++) {
/* last resort: catch NaN, INF and out-of-band errors */
- if (i < (unsigned)outputs.noutputs &&
+ if (i < outputs.noutputs &&
isfinite(outputs.output[i]) &&
outputs.output[i] >= -1.0f &&
outputs.output[i] <= 1.0f) {
@@ -516,7 +518,7 @@ HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
g_hil->set_pwm_rate(arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
// HIL always outputs at the alternate (usually faster) rate
break;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 59e90d86c..4c85c0cda 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -58,13 +58,14 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_hrt.h>
+#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
@@ -76,9 +77,10 @@
*/
#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
+#define HMC5883L_DEVICE_PATH "/dev/hmc5883"
-/* Max measurement rate is 160Hz */
-#define HMC5883_CONVERSION_INTERVAL (1000000 / 160) /* microseconds */
+/* Max measurement rate is 160Hz, however with 160 it will be set to 166 Hz, therefore workaround using 150 */
+#define HMC5883_CONVERSION_INTERVAL (1000000 / 150) /* microseconds */
#define ADDR_CONF_A 0x00
#define ADDR_CONF_B 0x01
@@ -148,14 +150,12 @@ private:
work_s _work;
unsigned _measure_ticks;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- mag_report *_reports;
+ RingBuffer *_reports;
mag_scale _scale;
float _range_scale;
float _range_ga;
bool _collect_phase;
+ int _class_instance;
orb_advert_t _mag_topic;
@@ -167,6 +167,8 @@ private:
bool _sensor_ok; /**< sensor was found and reports ok */
bool _calibrated; /**< the calibration is valid */
+ int _bus; /**< the bus the device is connected to */
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -190,6 +192,11 @@ private:
void stop();
/**
+ * Reset the device
+ */
+ int reset();
+
+ /**
* Perform the on-sensor scale calibration routine.
*
* @note The sensor will continue to provide measurements, these
@@ -303,9 +310,6 @@ private:
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
/*
* Driver 'main' command.
*/
@@ -313,20 +317,19 @@ extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
HMC5883::HMC5883(int bus) :
- I2C("HMC5883", MAG_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
+ I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
_measure_ticks(0),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
_mag_topic(-1),
+ _class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")),
_sensor_ok(false),
- _calibrated(false)
+ _calibrated(false),
+ _bus(bus)
{
// enable debug() calls
_debug_enabled = false;
@@ -348,9 +351,16 @@ HMC5883::~HMC5883()
/* make sure we are truly inactive */
stop();
- /* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
+
+ if (_class_instance != -1)
+ unregister_class_devname(MAG_DEVICE_PATH, _class_instance);
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
}
int
@@ -363,23 +373,14 @@ HMC5883::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _reports = new struct mag_report[_num_reports];
-
+ _reports = new RingBuffer(2, sizeof(mag_report));
if (_reports == nullptr)
goto out;
- _oldest_report = _next_report = 0;
-
- /* get a publish handle on the mag topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _mag_topic = orb_advertise(ORB_ID(sensor_mag), &_reports[0]);
-
- if (_mag_topic < 0)
- debug("failed to create sensor_mag object");
+ /* reset the device configuration */
+ reset();
- /* set range */
- set_range(_range_ga);
+ _class_instance = register_class_devname(MAG_DEVICE_PATH);
ret = OK;
/* sensor is ok, but not calibrated */
@@ -480,6 +481,7 @@ ssize_t
HMC5883::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct mag_report);
+ struct mag_report *mag_buf = reinterpret_cast<struct mag_report *>(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -488,17 +490,15 @@ HMC5883::read(struct file *filp, char *buffer, size_t buflen)
/* 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 (_reports->get(mag_buf)) {
+ ret += sizeof(struct mag_report);
+ mag_buf++;
}
}
@@ -509,7 +509,7 @@ HMC5883::read(struct file *filp, char *buffer, size_t buflen)
/* manual measurement - run one conversion */
/* XXX really it'd be nice to lock against other readers here */
do {
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* trigger a measurement */
if (OK != measure()) {
@@ -526,10 +526,9 @@ HMC5883::read(struct file *filp, char *buffer, size_t buflen)
break;
}
- /* state machine will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
-
+ if (_reports->get(mag_buf)) {
+ ret = sizeof(struct mag_report);
+ }
} while (0);
return ret;
@@ -539,108 +538,105 @@ int
HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
-
case SENSORIOCSPOLLRATE: {
- switch (arg) {
+ switch (arg) {
- /* switching to manual polling */
- case SENSOR_POLLRATE_MANUAL:
- stop();
- _measure_ticks = 0;
- return OK;
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
- /* external signalling (DRDY) not supported */
- case SENSOR_POLLRATE_EXTERNAL:
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
- /* zero would be bad */
- case 0:
- return -EINVAL;
+ /* 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 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(HMC5883_CONVERSION_INTERVAL);
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(HMC5883_CONVERSION_INTERVAL);
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
- return OK;
- }
+ return OK;
+ }
- /* adjust to a legal polling interval in Hz */
- default: {
- /* do we need to start internal polling? */
- bool want_start = (_measure_ticks == 0);
+ /* 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);
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
- /* check against maximum rate */
- if (ticks < USEC2TICK(HMC5883_CONVERSION_INTERVAL))
- return -EINVAL;
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(HMC5883_CONVERSION_INTERVAL))
+ return -EINVAL;
- /* update interval for next measurement */
- _measure_ticks = ticks;
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
- return OK;
- }
+ return OK;
}
}
+ }
case SENSORIOCGPOLLRATE:
if (_measure_ticks == 0)
return SENSOR_POLLRATE_MANUAL;
- return (1000 / _measure_ticks);
+ return 1000000/TICK2USEC(_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))
+ if ((arg < 1) || (arg > 100))
return -EINVAL;
- /* allocate new buffer */
- struct mag_report *buf = new struct mag_report[arg];
-
- if (nullptr == buf)
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
return -ENOMEM;
-
- /* reset the measurement state machine with the new buffer, free the old */
- stop();
- delete[] _reports;
- _num_reports = arg;
- _reports = buf;
- start();
+ }
+ irqrestore(flags);
return OK;
}
case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
- /* XXX implement this */
- return -EINVAL;
+ return reset();
case MAGIOCSSAMPLERATE:
- /* not supported, always 1 sample per poll */
- return -EINVAL;
+ /* same as pollrate because device is in single measurement mode*/
+ return ioctl(filp, SENSORIOCSPOLLRATE, arg);
+
+ case MAGIOCGSAMPLERATE:
+ /* same as pollrate because device is in single measurement mode*/
+ return 1000000/TICK2USEC(_measure_ticks);
case MAGIOCSRANGE:
return set_range(arg);
+ case MAGIOCGRANGE:
+ return _range_ga;
+
case MAGIOCSLOWPASS:
+ case MAGIOCGLOWPASS:
/* not supported, no internal filtering */
return -EINVAL;
@@ -665,6 +661,12 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCSELFTEST:
return check_calibration();
+ case MAGIOCGEXTERNAL:
+ if (_bus == PX4_I2C_BUS_EXPANSION)
+ return 1;
+ else
+ return 0;
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -676,7 +678,7 @@ HMC5883::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&HMC5883::cycle_trampoline, this, 1);
@@ -688,6 +690,13 @@ HMC5883::stop()
work_cancel(HPWORK, &_work);
}
+int
+HMC5883::reset()
+{
+ /* set range */
+ return set_range(_range_ga);
+}
+
void
HMC5883::cycle_trampoline(void *arg)
{
@@ -778,9 +787,11 @@ HMC5883::collect()
perf_begin(_sample_perf);
+ struct mag_report new_report;
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
- _reports[_next_report].timestamp = hrt_absolute_time();
+ new_report.timestamp = hrt_absolute_time();
+ new_report.error_count = perf_event_count(_comms_errors);
/*
* @note We could read the status register here, which could tell us that
@@ -810,8 +821,10 @@ HMC5883::collect()
*/
if ((abs(report.x) > 2048) ||
(abs(report.y) > 2048) ||
- (abs(report.z) > 2048))
+ (abs(report.z) > 2048)) {
+ perf_count(_comms_errors);
goto out;
+ }
/*
* RAW outputs
@@ -819,58 +832,47 @@ HMC5883::collect()
* to align the sensor axes with the board, x and y need to be flipped
* and y needs to be negated
*/
- _reports[_next_report].x_raw = report.y;
- _reports[_next_report].y_raw = ((report.x == -32768) ? 32767 : -report.x);
+ new_report.x_raw = report.y;
+ new_report.y_raw = -report.x;
/* z remains z */
- _reports[_next_report].z_raw = report.z;
+ new_report.z_raw = report.z;
/* scale values for output */
- /*
- * 1) Scale raw value to SI units using scaling from datasheet.
- * 2) Subtract static offset (in SI units)
- * 3) Scale the statically calibrated values with a linear
- * dynamically obtained factor
- *
- * Note: the static sensor offset is the number the sensor outputs
- * at a nominally 'zero' input. Therefore the offset has to
- * be subtracted.
- *
- * Example: A gyro outputs a value of 74 at zero angular rate
- * the offset is 74 from the origin and subtracting
- * 74 from all measurements centers them around zero.
- */
-
#ifdef PX4_I2C_BUS_ONBOARD
if (_bus == PX4_I2C_BUS_ONBOARD) {
- /* to align the sensor axes with the board, x and y need to be flipped */
- _reports[_next_report].x = ((report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
- /* flip axes and negate value for y */
- _reports[_next_report].y = ((((report.x == -32768) ? 32767 : -report.x) * _range_scale) - _scale.y_offset) * _scale.y_scale;
- /* z remains z */
- _reports[_next_report].z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
- } else {
-#endif
- /* XXX axis assignment of external sensor is yet unknown */
- _reports[_next_report].x = ((report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
- /* flip axes and negate value for y */
- _reports[_next_report].y = ((((report.x == -32768) ? 32767 : -report.x) * _range_scale) - _scale.y_offset) * _scale.y_scale;
- /* z remains z */
- _reports[_next_report].z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
-#ifdef PX4_I2C_BUS_ONBOARD
- }
+ // convert onboard so it matches offboard for the
+ // scaling below
+ report.y = -report.y;
+ report.x = -report.x;
+ }
#endif
- /* publish it */
- orb_publish(ORB_ID(sensor_mag), _mag_topic, &_reports[_next_report]);
+ /* the standard external mag by 3DR has x pointing to the
+ * right, y pointing backwards, and z down, therefore switch x
+ * and y and invert y */
+ new_report.x = ((-report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
+ /* flip axes and negate value for y */
+ new_report.y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
+ /* z remains z */
+ new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
+ if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) {
- /* if we are running up against the oldest report, toss it */
- if (_next_report == _oldest_report) {
+ if (_mag_topic != -1) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report);
+ } else {
+ _mag_topic = orb_advertise(ORB_ID(sensor_mag), &new_report);
+
+ if (_mag_topic < 0)
+ debug("failed to create sensor_mag publication");
+ }
+ }
+
+ /* post a report to the ring */
+ if (_reports->force(&new_report)) {
perf_count(_buffer_overflows);
- INCREMENT(_oldest_report, _num_reports);
}
/* notify anyone waiting for data */
@@ -888,6 +890,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
struct mag_report report;
ssize_t sz;
int ret = 1;
+ uint8_t good_count = 0;
// XXX do something smarter here
int fd = (int)enable;
@@ -910,30 +913,16 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
1.0f,
};
- float avg_excited[3] = {0.0f, 0.0f, 0.0f};
- unsigned i;
+ float sum_excited[3] = {0.0f, 0.0f, 0.0f};
- warnx("starting mag scale calibration");
+ /* expected axis scaling. The datasheet says that 766 will
+ * be places in the X and Y axes and 713 in the Z
+ * axis. Experiments show that in fact 766 is placed in X,
+ * and 713 in Y and Z. This is relative to a base of 660
+ * LSM/Ga, giving 1.16 and 1.08 */
+ float expected_cal[3] = { 1.16f, 1.08f, 1.08f };
- /* do a simple demand read */
- sz = read(filp, (char *)&report, sizeof(report));
-
- if (sz != sizeof(report)) {
- warn("immediate read failed");
- ret = 1;
- goto out;
- }
-
- warnx("current measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
- warnx("time: %lld", report.timestamp);
- warnx("sampling 500 samples for scaling offset");
-
- /* set the queue depth to 10 */
- if (OK != ioctl(filp, SENSORIOCSQUEUEDEPTH, 10)) {
- warn("failed to set queue depth");
- ret = 1;
- goto out;
- }
+ warnx("starting mag scale calibration");
/* start the sensor polling at 50 Hz */
if (OK != ioctl(filp, SENSORIOCSPOLLRATE, 50)) {
@@ -942,8 +931,9 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
goto out;
}
- /* Set to 2.5 Gauss */
- if (OK != ioctl(filp, MAGIOCSRANGE, 2)) {
+ /* Set to 2.5 Gauss. We ask for 3 to get the right part of
+ * the chained if statement above. */
+ if (OK != ioctl(filp, MAGIOCSRANGE, 3)) {
warnx("failed to set 2.5 Ga range");
ret = 1;
goto out;
@@ -967,8 +957,8 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
goto out;
}
- /* read the sensor 10x and report each value */
- for (i = 0; i < 500; i++) {
+ // discard 10 samples to let the sensor settle
+ for (uint8_t i = 0; i < 10; i++) {
struct pollfd fds;
/* wait for data to be ready */
@@ -986,32 +976,69 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
if (sz != sizeof(report)) {
warn("periodic read failed");
+ ret = -EIO;
goto out;
+ }
+ }
- } else {
- avg_excited[0] += report.x;
- avg_excited[1] += report.y;
- avg_excited[2] += report.z;
+ /* read the sensor up to 50x, stopping when we have 10 good values */
+ for (uint8_t i = 0; i < 50 && good_count < 10; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = ::poll(&fds, 1, 2000);
+
+ if (ret != 1) {
+ warn("timed out waiting for sensor data");
+ goto out;
+ }
+
+ /* now go get it */
+ sz = ::read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ warn("periodic read failed");
+ ret = -EIO;
+ goto out;
+ }
+ float cal[3] = {fabsf(expected_cal[0] / report.x),
+ fabsf(expected_cal[1] / report.y),
+ fabsf(expected_cal[2] / report.z)};
+
+ if (cal[0] > 0.7f && cal[0] < 1.35f &&
+ cal[1] > 0.7f && cal[1] < 1.35f &&
+ cal[2] > 0.7f && cal[2] < 1.35f) {
+ good_count++;
+ sum_excited[0] += cal[0];
+ sum_excited[1] += cal[1];
+ sum_excited[2] += cal[2];
}
//warnx("periodic read %u", i);
//warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
+ //warnx("cal: %.6f %.6f %.6f", (double)cal[0], (double)cal[1], (double)cal[2]);
}
- avg_excited[0] /= i;
- avg_excited[1] /= i;
- avg_excited[2] /= i;
+ if (good_count < 5) {
+ warn("failed calibration");
+ ret = -EIO;
+ goto out;
+ }
- warnx("done. Performed %u reads", i);
- warnx("measurement avg: %.6f %.6f %.6f", (double)avg_excited[0], (double)avg_excited[1], (double)avg_excited[2]);
+#if 0
+ warnx("measurement avg: %.6f %.6f %.6f",
+ (double)sum_excited[0]/good_count,
+ (double)sum_excited[1]/good_count,
+ (double)sum_excited[2]/good_count);
+#endif
float scaling[3];
- /* calculate axis scaling */
- scaling[0] = fabsf(1.16f / avg_excited[0]);
- /* second axis inverted */
- scaling[1] = fabsf(1.16f / -avg_excited[1]);
- scaling[2] = fabsf(1.08f / avg_excited[2]);
+ scaling[0] = sum_excited[0] / good_count;
+ scaling[1] = sum_excited[1] / good_count;
+ scaling[2] = sum_excited[2] / good_count;
warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
@@ -1111,10 +1138,12 @@ int HMC5883::check_calibration()
SUBSYSTEM_TYPE_MAG};
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);
+ if (!(_pub_blocked)) {
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
}
}
@@ -1142,6 +1171,8 @@ int HMC5883::set_excitement(unsigned enable)
conf_reg &= ~0x03;
}
+ // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)conf_reg);
+
ret = write_reg(ADDR_CONF_A, conf_reg);
if (OK != ret)
@@ -1150,6 +1181,8 @@ int HMC5883::set_excitement(unsigned enable)
uint8_t conf_reg_ret;
read_reg(ADDR_CONF_A, conf_reg_ret);
+ //print_info();
+
return !(conf_reg == conf_reg_ret);
}
@@ -1188,8 +1221,11 @@ HMC5883::print_info()
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);
+ printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
+ printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
+ (double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
+ (double)1.0/_range_scale, (double)_range_ga);
+ _reports->print_info("report queue");
}
/**
@@ -1221,7 +1257,8 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
/* create the driver, attempt expansion bus first */
g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION);
@@ -1245,7 +1282,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1277,10 +1314,10 @@ test()
ssize_t sz;
int ret;
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -1292,7 +1329,12 @@ test()
warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
warnx("time: %lld", report.timestamp);
- /* set the queue depth to 10 */
+ /* check if mag is onboard or external */
+ if ((ret = ioctl(fd, MAGIOCGEXTERNAL, 0)) < 0)
+ errx(1, "failed to get if mag is onboard or external");
+ warnx("device active: %s", ret ? "external" : "onboard");
+
+ /* set the queue depth to 5 */
if (OK != ioctl(fd, SENSORIOCSQUEUEDEPTH, 10))
errx(1, "failed to set queue depth");
@@ -1372,10 +1414,10 @@ int calibrate()
{
int ret;
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", MAG_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
if (OK != (ret = ioctl(fd, MAGIOCCALIBRATE, fd))) {
warnx("failed to enable sensor calibration mode");
@@ -1397,7 +1439,7 @@ int calibrate()
void
reset()
{
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "failed ");
diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp
new file mode 100644
index 000000000..cb8bbba37
--- /dev/null
+++ b/src/drivers/hott/comms.cpp
@@ -0,0 +1,92 @@
+/****************************************************************************
+ *
+ * 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 comms.c
+ * @author Simon Wilks <sjwilks@gmail.com>
+ *
+ */
+
+#include "comms.h"
+
+#include <fcntl.h>
+#include <stdio.h>
+#include <sys/ioctl.h>
+#include <systemlib/err.h>
+#include <termios.h>
+
+int
+open_uart(const char *device)
+{
+ /* baud rate */
+ static const speed_t speed = B19200;
+
+ /* open uart */
+ const int uart = open(device, O_RDWR | O_NOCTTY);
+
+ if (uart < 0) {
+ err(1, "Error opening port: %s", device);
+ }
+
+ /* Back up the original uart configuration to restore it after exit */
+ int termios_state;
+ struct termios uart_config_original;
+ if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) {
+ close(uart);
+ err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state);
+ }
+
+ /* Fill the struct for the new configuration */
+ struct termios uart_config;
+ tcgetattr(uart, &uart_config);
+
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+
+ /* Set baud rate */
+ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
+ close(uart);
+ err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)",
+ device, termios_state);
+ }
+
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ close(uart);
+ err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device);
+ }
+
+ /* Activate single wire mode */
+ ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
+
+ return uart;
+}
diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h
new file mode 100644
index 000000000..f5608122f
--- /dev/null
+++ b/src/drivers/hott/comms.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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 comms.h
+ * @author Simon Wilks <sjwilks@gmail.com>
+ *
+ */
+
+
+#ifndef COMMS_H_
+#define COMMS_H
+
+int open_uart(const char *device);
+
+#endif /* COMMS_H_ */
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
new file mode 100644
index 000000000..a3d3a3933
--- /dev/null
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -0,0 +1,238 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 hott_sensors.c
+ * @author Simon Wilks <sjwilks@gmail.com>
+ *
+ * Graupner HoTT sensor driver implementation.
+ *
+ * Poll any sensors connected to the PX4 via the telemetry wire.
+ */
+
+#include <fcntl.h>
+#include <nuttx/config.h>
+#include <poll.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <sys/ioctl.h>
+#include <unistd.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include "../comms.h"
+#include "../messages.h"
+
+#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
+
+/* Oddly, ERROR is not defined for C++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static int thread_should_exit = false; /**< Deamon exit flag */
+static int thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+static const char daemon_name[] = "hott_sensors";
+static const char commandline_usage[] = "usage: hott_sensors start|status|stop [-d <device>]";
+
+/**
+ * Deamon management function.
+ */
+extern "C" __EXPORT int hott_sensors_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of daemon.
+ */
+int hott_sensors_thread_main(int argc, char *argv[]);
+
+static int recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id);
+static int send_poll(int uart, uint8_t *buffer, size_t size);
+
+int
+send_poll(int uart, uint8_t *buffer, size_t size)
+{
+ for (size_t i = 0; i < size; i++) {
+ write(uart, &buffer[i], sizeof(buffer[i]));
+
+ /* Sleep before sending the next byte. */
+ usleep(POST_WRITE_DELAY_IN_USECS);
+ }
+
+ /* A hack the reads out what was written so the next read from the receiver doesn't get it. */
+ /* TODO: Fix this!! */
+ uint8_t dummy[size];
+ read(uart, &dummy, size);
+
+ return OK;
+}
+
+int
+recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id)
+{
+ static const int timeout_ms = 1000;
+
+ struct pollfd fds;
+ fds.fd = uart;
+ fds.events = POLLIN;
+
+ // XXX should this poll be inside the while loop???
+ if (poll(&fds, 1, timeout_ms) > 0) {
+ int i = 0;
+ bool stop_byte_read = false;
+ while (true) {
+ read(uart, &buffer[i], sizeof(buffer[i]));
+
+ if (stop_byte_read) {
+ // XXX process checksum
+ *size = ++i;
+ return OK;
+ }
+ // XXX can some other field not have the STOP BYTE value?
+ if (buffer[i] == STOP_BYTE) {
+ *id = buffer[1];
+ stop_byte_read = true;
+ }
+ i++;
+ }
+ }
+ return ERROR;
+}
+
+int
+hott_sensors_thread_main(int argc, char *argv[])
+{
+ warnx("starting");
+
+ thread_running = true;
+
+ const char *device = DEFAULT_UART;
+
+ /* read commandline arguments */
+ for (int i = 0; i < argc && argv[i]; i++) {
+ if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set
+ if (argc > i + 1) {
+ device = argv[i + 1];
+
+ } else {
+ thread_running = false;
+ errx(1, "missing parameter to -d\n%s", commandline_usage);
+ }
+ }
+ }
+
+ /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
+ const int uart = open_uart(device);
+ if (uart < 0) {
+ errx(1, "Failed opening HoTT UART, exiting.");
+ thread_running = false;
+ }
+
+ init_pub_messages();
+
+ uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE];
+ size_t size = 0;
+ uint8_t id = 0;
+ while (!thread_should_exit) {
+ // Currently we only support a General Air Module sensor.
+ build_gam_request(&buffer[0], &size);
+ send_poll(uart, buffer, size);
+
+ // The sensor will need a little time before it starts sending.
+ usleep(5000);
+
+ recv_data(uart, &buffer[0], &size, &id);
+
+ // Determine which moduel sent it and process accordingly.
+ if (id == GAM_SENSOR_ID) {
+ publish_gam_message(buffer);
+ } else {
+ warnx("Unknown sensor ID: %d", id);
+ }
+ }
+
+ warnx("exiting");
+ close(uart);
+ thread_running = false;
+
+ return 0;
+}
+
+/**
+ * Process command line arguments and start the daemon.
+ */
+int
+hott_sensors_main(int argc, char *argv[])
+{
+ if (argc < 1) {
+ errx(1, "missing command\n%s", commandline_usage);
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("deamon already running");
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn_cmd(daemon_name,
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT,
+ 1024,
+ hott_sensors_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("daemon is running");
+
+ } else {
+ warnx("daemon not started");
+ }
+
+ exit(0);
+ }
+
+ errx(1, "unrecognized command\n%s", commandline_usage);
+}
diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk
new file mode 100644
index 000000000..b5f5762ba
--- /dev/null
+++ b/src/drivers/hott/hott_sensors/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Graupner HoTT Sensors application.
+#
+
+MODULE_COMMAND = hott_sensors
+
+SRCS = hott_sensors.cpp \
+ ../messages.cpp \
+ ../comms.cpp
diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index 60f3f3e96..d293f9954 100644
--- a/src/drivers/hott_telemetry/hott_telemetry_main.c
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -41,7 +41,6 @@
* The HoTT receiver polls each device at a regular interval at which point
* a data packet can be returned if necessary.
*
- * TODO: Add support for at least the vario and GPS sensor data.
*/
#include <fcntl.h>
@@ -50,124 +49,78 @@
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
-#include <termios.h>
#include <sys/ioctl.h>
#include <unistd.h>
+#include <systemlib/err.h>
#include <systemlib/systemlib.h>
-#include "messages.h"
+#include "../comms.h"
+#include "../messages.h"
+
+#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */
+
+/* Oddly, ERROR is not defined for C++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
static int thread_should_exit = false; /**< Deamon exit flag */
static int thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
-static char *daemon_name = "hott_telemetry";
-static char *commandline_usage = "usage: hott_telemetry start|status|stop [-d <device>]";
-
+static const char daemon_name[] = "hott_telemetry";
+static const char commandline_usage[] = "usage: hott_telemetry start|status|stop [-d <device>]";
-/* A little console messaging experiment - console helper macro */
-#define FATAL_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg); exit(1);
-#define ERROR_MSG(_msg) fprintf(stderr, "[%s] %s\n", daemon_name, _msg);
-#define INFO_MSG(_msg) printf("[%s] %s\n", daemon_name, _msg);
/**
* Deamon management function.
*/
-__EXPORT int hott_telemetry_main(int argc, char *argv[]);
+extern "C" __EXPORT int hott_telemetry_main(int argc, char *argv[]);
/**
- * Mainloop of deamon.
+ * Mainloop of daemon.
*/
int hott_telemetry_thread_main(int argc, char *argv[]);
-static int read_data(int uart, int *id);
-static int send_data(int uart, uint8_t *buffer, int size);
+static int recv_req_id(int uart, uint8_t *id);
+static int send_data(int uart, uint8_t *buffer, size_t size);
-static int open_uart(const char *device, struct termios *uart_config_original)
+int
+recv_req_id(int uart, uint8_t *id)
{
- /* baud rate */
- int speed = B19200;
- int uart;
-
- /* open uart */
- uart = open(device, O_RDWR | O_NOCTTY);
-
- if (uart < 0) {
- char msg[80];
- sprintf(msg, "Error opening port: %s\n", device);
- FATAL_MSG(msg);
- }
-
- /* Try to set baud rate */
- struct termios uart_config;
- int termios_state;
-
- /* Back up the original uart configuration to restore it after exit */
- char msg[80];
+ static const int timeout_ms = 1000; // TODO make it a define
- if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- sprintf(msg, "Error getting baudrate / termios config for %s: %d\n", device, termios_state);
- close(uart);
- FATAL_MSG(msg);
- }
-
- /* Fill the struct for the new configuration */
- tcgetattr(uart, &uart_config);
-
- /* Clear ONLCR flag (which appends a CR for every LF) */
- uart_config.c_oflag &= ~ONLCR;
-
- /* Set baud rate */
- if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- sprintf(msg, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n",
- device, termios_state);
- close(uart);
- FATAL_MSG(msg);
- }
+ uint8_t mode;
+
+ struct pollfd fds;
+ fds.fd = uart;
+ fds.events = POLLIN;
- if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- sprintf(msg, "Error setting baudrate / termios config for %s (tcsetattr)\n", device);
- close(uart);
- FATAL_MSG(msg);
- }
-
- /* Activate single wire mode */
- ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
-
- return uart;
-}
-
-int read_data(int uart, int *id)
-{
- const int timeout = 1000;
- struct pollfd fds[] = { { .fd = uart, .events = POLLIN } };
-
- char mode;
-
- if (poll(fds, 1, timeout) > 0) {
+ if (poll(&fds, 1, timeout_ms) > 0) {
/* Get the mode: binary or text */
- read(uart, &mode, 1);
- /* Read the device ID being polled */
- read(uart, id, 1);
+ read(uart, &mode, sizeof(mode));
/* if we have a binary mode request */
if (mode != BINARY_MODE_REQUEST_ID) {
return ERROR;
}
+ /* Read the device ID being polled */
+ read(uart, id, sizeof(*id));
} else {
- ERROR_MSG("UART timeout on TX/RX port");
+ warnx("UART timeout on TX/RX port");
return ERROR;
}
return OK;
}
-int send_data(int uart, uint8_t *buffer, int size)
+int
+send_data(int uart, uint8_t *buffer, size_t size)
{
usleep(POST_READ_DELAY_IN_USECS);
uint16_t checksum = 0;
-
- for (int i = 0; i < size; i++) {
+ for (size_t i = 0; i < size; i++) {
if (i == size - 1) {
/* Set the checksum: the first uint8_t is taken as the checksum. */
buffer[i] = checksum & 0xff;
@@ -176,7 +129,7 @@ int send_data(int uart, uint8_t *buffer, int size)
checksum += buffer[i];
}
- write(uart, &buffer[i], 1);
+ write(uart, &buffer[i], sizeof(buffer[i]));
/* Sleep before sending the next byte. */
usleep(POST_WRITE_DELAY_IN_USECS);
@@ -190,13 +143,14 @@ int send_data(int uart, uint8_t *buffer, int size)
return OK;
}
-int hott_telemetry_thread_main(int argc, char *argv[])
+int
+hott_telemetry_thread_main(int argc, char *argv[])
{
- INFO_MSG("starting");
+ warnx("starting");
thread_running = true;
- char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */
+ const char *device = DEFAULT_UART;
/* read commandline arguments */
for (int i = 0; i < argc && argv[i]; i++) {
@@ -206,45 +160,55 @@ int hott_telemetry_thread_main(int argc, char *argv[])
} else {
thread_running = false;
- ERROR_MSG("missing parameter to -d");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "missing parameter to -d\n%s", commandline_usage);
}
}
}
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
- struct termios uart_config_original;
- int uart = open_uart(device, &uart_config_original);
-
+ const int uart = open_uart(device);
if (uart < 0) {
- ERROR_MSG("Failed opening HoTT UART, exiting.");
+ errx(1, "Failed opening HoTT UART, exiting.");
thread_running = false;
- exit(ERROR);
}
- messages_init();
-
- uint8_t buffer[MESSAGE_BUFFER_SIZE];
- int size = 0;
- int id = 0;
+ init_sub_messages();
+ uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE];
+ size_t size = 0;
+ uint8_t id = 0;
+ bool connected = true;
while (!thread_should_exit) {
- if (read_data(uart, &id) == OK) {
+ // Listen for and serve poll from the receiver.
+ if (recv_req_id(uart, &id) == OK) {
+ if (!connected) {
+ connected = true;
+ warnx("OK");
+ }
+
switch (id) {
- case ELECTRIC_AIR_MODULE:
+ case EAM_SENSOR_ID:
build_eam_response(buffer, &size);
break;
+ case GAM_SENSOR_ID:
+ build_gam_response(buffer, &size);
+ break;
+ case GPS_SENSOR_ID:
+ build_gps_response(buffer, &size);
+ break;
default:
continue; // Not a module we support.
}
send_data(uart, buffer, size);
+ } else {
+ connected = false;
+ warnx("syncing");
}
}
- INFO_MSG("exiting");
+ warnx("exiting");
close(uart);
@@ -254,27 +218,26 @@ int hott_telemetry_thread_main(int argc, char *argv[])
}
/**
- * Process command line arguments and tart the daemon.
+ * Process command line arguments and start the daemon.
*/
-int hott_telemetry_main(int argc, char *argv[])
+int
+hott_telemetry_main(int argc, char *argv[])
{
if (argc < 1) {
- ERROR_MSG("missing command");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "missing command\n%s", commandline_usage);
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- INFO_MSG("deamon already running");
+ warnx("deamon already running");
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn_cmd("hott_telemetry",
+ deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 40,
+ SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -288,19 +251,14 @@ int hott_telemetry_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- INFO_MSG("daemon is running");
+ warnx("daemon is running");
} else {
- INFO_MSG("daemon not started");
+ warnx("daemon not started");
}
exit(0);
}
- ERROR_MSG("unrecognized command");
- ERROR_MSG(commandline_usage);
- exit(1);
+ errx(1, "unrecognized command\n%s", commandline_usage);
}
-
-
-
diff --git a/src/drivers/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk
index def1d59e9..b19cbd14c 100644
--- a/src/drivers/hott_telemetry/module.mk
+++ b/src/drivers/hott/hott_telemetry/module.mk
@@ -32,10 +32,11 @@
############################################################################
#
-# Graupner HoTT Telemetry application.
+# Graupner HoTT Telemetry applications.
#
MODULE_COMMAND = hott_telemetry
-SRCS = hott_telemetry_main.c \
- messages.c
+SRCS = hott_telemetry.cpp \
+ ../messages.cpp \
+ ../comms.cpp
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
new file mode 100644
index 000000000..bb8d45bea
--- /dev/null
+++ b/src/drivers/hott/messages.cpp
@@ -0,0 +1,330 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 messages.c
+ *
+ */
+
+#include "messages.h"
+
+#include <math.h>
+#include <stdio.h>
+#include <string.h>
+#include <geo/geo.h>
+#include <unistd.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/esc_status.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_gps_position.h>
+
+/* The board is very roughly 5 deg warmer than the surrounding air */
+#define BOARD_TEMP_OFFSET_DEG 5
+
+static int _battery_sub = -1;
+static int _gps_sub = -1;
+static int _home_sub = -1;
+static int _sensor_sub = -1;
+static int _airspeed_sub = -1;
+static int _esc_sub = -1;
+
+static orb_advert_t _esc_pub;
+struct esc_status_s _esc;
+
+static bool _home_position_set = false;
+static double _home_lat = 0.0d;
+static double _home_lon = 0.0d;
+
+void
+init_sub_messages(void)
+{
+ _battery_sub = orb_subscribe(ORB_ID(battery_status));
+ _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ _home_sub = orb_subscribe(ORB_ID(home_position));
+ _sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _esc_sub = orb_subscribe(ORB_ID(esc_status));
+}
+
+void
+init_pub_messages(void)
+{
+ memset(&_esc, 0, sizeof(_esc));
+ _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
+}
+
+void
+build_gam_request(uint8_t *buffer, size_t *size)
+{
+ struct gam_module_poll_msg msg;
+ *size = sizeof(msg);
+ memset(&msg, 0, *size);
+
+ msg.mode = BINARY_MODE_REQUEST_ID;
+ msg.id = GAM_SENSOR_ID;
+
+ memcpy(buffer, &msg, *size);
+}
+
+void
+publish_gam_message(const uint8_t *buffer)
+{
+ struct gam_module_msg msg;
+ size_t size = sizeof(msg);
+ memset(&msg, 0, size);
+ memcpy(&msg, buffer, size);
+
+ /* announce the esc if needed, just publish else */
+ if (_esc_pub > 0) {
+ orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
+ } else {
+ _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
+ }
+
+ // Publish it.
+ _esc.esc_count = 1;
+ _esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
+
+ _esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
+ _esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
+ _esc.esc[0].esc_temperature = msg.temperature1 - 20;
+ _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
+ _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
+}
+
+void
+build_eam_response(uint8_t *buffer, size_t *size)
+{
+ /* get a local copy of the current sensor values */
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+ orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw);
+
+ /* get a local copy of the battery data */
+ struct battery_status_s battery;
+ memset(&battery, 0, sizeof(battery));
+ orb_copy(ORB_ID(battery_status), _battery_sub, &battery);
+
+ struct eam_module_msg msg;
+ *size = sizeof(msg);
+ memset(&msg, 0, *size);
+
+ msg.start = START_BYTE;
+ msg.eam_sensor_id = EAM_SENSOR_ID;
+ msg.sensor_text_id = EAM_SENSOR_TEXT_ID;
+
+ msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20);
+ msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG;
+
+ msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10);
+
+ uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500);
+ msg.altitude_L = (uint8_t)alt & 0xff;
+ msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
+
+ /* get a local copy of the airspeed data */
+ struct airspeed_s airspeed;
+ memset(&airspeed, 0, sizeof(airspeed));
+ orb_copy(ORB_ID(airspeed), _airspeed_sub, &airspeed);
+
+ uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f);
+ msg.speed_L = (uint8_t)speed & 0xff;
+ msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
+
+ msg.stop = STOP_BYTE;
+ memcpy(buffer, &msg, *size);
+}
+
+void
+build_gam_response(uint8_t *buffer, size_t *size)
+{
+ /* get a local copy of the ESC Status values */
+ struct esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+ orb_copy(ORB_ID(esc_status), _esc_sub, &esc);
+
+ struct gam_module_msg msg;
+ *size = sizeof(msg);
+ memset(&msg, 0, *size);
+
+ msg.start = START_BYTE;
+ msg.gam_sensor_id = GAM_SENSOR_ID;
+ msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
+
+ msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20);
+ msg.temperature2 = 20; // 0 deg. C.
+
+ uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage);
+ msg.main_voltage_L = (uint8_t)voltage & 0xff;
+ msg.main_voltage_H = (uint8_t)(voltage >> 8) & 0xff;
+
+ uint16_t current = (uint16_t)(esc.esc[0].esc_current);
+ msg.current_L = (uint8_t)current & 0xff;
+ msg.current_H = (uint8_t)(current >> 8) & 0xff;
+
+ uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
+ msg.rpm_L = (uint8_t)rpm & 0xff;
+ msg.rpm_H = (uint8_t)(rpm >> 8) & 0xff;
+
+ msg.stop = STOP_BYTE;
+ memcpy(buffer, &msg, *size);
+}
+
+void
+build_gps_response(uint8_t *buffer, size_t *size)
+{
+ /* get a local copy of the current sensor values */
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+ orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw);
+
+ /* get a local copy of the battery data */
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
+ orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &gps);
+
+ struct gps_module_msg msg;
+ *size = sizeof(msg);
+ memset(&msg, 0, *size);
+
+ msg.start = START_BYTE;
+ msg.sensor_id = GPS_SENSOR_ID;
+ msg.sensor_text_id = GPS_SENSOR_TEXT_ID;
+
+ msg.gps_num_sat = gps.satellites_visible;
+
+ /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */
+ msg.gps_fix_char = (uint8_t)(gps.fix_type + 48);
+ msg.gps_fix = (uint8_t)(gps.fix_type + 48);
+
+ /* No point collecting more data if we don't have a 3D fix yet */
+ if (gps.fix_type > 2) {
+ /* Current flight direction */
+ msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F);
+
+ /* GPS speed */
+ uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6f);
+ msg.gps_speed_L = (uint8_t)speed & 0xff;
+ msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff;
+
+ /* Get latitude in degrees, minutes and seconds */
+ double lat = ((double)(gps.lat))*1e-7d;
+
+ /* Set the N or S specifier */
+ msg.latitude_ns = 0;
+ if (lat < 0) {
+ msg.latitude_ns = 1;
+ lat = abs(lat);
+ }
+
+ int deg;
+ int min;
+ int sec;
+ convert_to_degrees_minutes_seconds(lat, &deg, &min, &sec);
+
+ uint16_t lat_min = (uint16_t)(deg * 100 + min);
+ msg.latitude_min_L = (uint8_t)lat_min & 0xff;
+ msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff;
+ uint16_t lat_sec = (uint16_t)(sec);
+ msg.latitude_sec_L = (uint8_t)lat_sec & 0xff;
+ msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff;
+
+ /* Get longitude in degrees, minutes and seconds */
+ double lon = ((double)(gps.lon))*1e-7d;
+
+ /* Set the E or W specifier */
+ msg.longitude_ew = 0;
+ if (lon < 0) {
+ msg.longitude_ew = 1;
+ lon = abs(lon);
+ }
+
+ convert_to_degrees_minutes_seconds(lon, &deg, &min, &sec);
+
+ uint16_t lon_min = (uint16_t)(deg * 100 + min);
+ msg.longitude_min_L = (uint8_t)lon_min & 0xff;
+ msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff;
+ uint16_t lon_sec = (uint16_t)(sec);
+ msg.longitude_sec_L = (uint8_t)lon_sec & 0xff;
+ msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff;
+
+ /* Altitude */
+ uint16_t alt = (uint16_t)(gps.alt*1e-3f + 500.0f);
+ msg.altitude_L = (uint8_t)alt & 0xff;
+ msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
+
+ /* Get any (and probably only ever one) _home_sub postion report */
+ bool updated;
+ orb_check(_home_sub, &updated);
+ if (updated) {
+ /* get a local copy of the home position data */
+ struct home_position_s home;
+ memset(&home, 0, sizeof(home));
+ orb_copy(ORB_ID(home_position), _home_sub, &home);
+
+ _home_lat = ((double)(home.lat))*1e-7d;
+ _home_lon = ((double)(home.lon))*1e-7d;
+ _home_position_set = true;
+ }
+
+ /* Distance from home */
+ if (_home_position_set) {
+ uint16_t dist = (uint16_t)get_distance_to_next_waypoint(_home_lat, _home_lon, lat, lon);
+
+ msg.distance_L = (uint8_t)dist & 0xff;
+ msg.distance_H = (uint8_t)(dist >> 8) & 0xff;
+
+ /* Direction back to home */
+ uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(_home_lat, _home_lon, lat, lon) * M_RAD_TO_DEG_F);
+ msg.home_direction = (uint8_t)bearing >> 1;
+ }
+ }
+
+ msg.stop = STOP_BYTE;
+ memcpy(buffer, &msg, *size);
+}
+
+void
+convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec)
+{
+ *deg = (int)val;
+
+ double delta = val - *deg;
+ const double min_d = delta * 60.0d;
+ *min = (int)min_d;
+ delta = min_d - *min;
+ *sec = (int)(delta * 10000.0d);
+}
diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h
new file mode 100644
index 000000000..224f8fc56
--- /dev/null
+++ b/src/drivers/hott/messages.h
@@ -0,0 +1,249 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * 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 messages.h
+ * @author Simon Wilks <sjwilks@gmail.com>
+ *
+ * Graupner HoTT Telemetry message generation.
+ *
+ */
+#ifndef MESSAGES_H_
+#define MESSAGES_H
+
+#include <stdlib.h>
+
+/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request.
+ * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting
+ * the message after the read which takes some milliseconds.
+ */
+#define POST_READ_DELAY_IN_USECS 4000
+/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower
+ * values can be used in practise though.
+ */
+#define POST_WRITE_DELAY_IN_USECS 2000
+
+// Protocol constants.
+#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request.
+#define START_BYTE 0x7c
+#define STOP_BYTE 0x7d
+#define TEMP_ZERO_CELSIUS 0x14
+
+/* The GAM Module poll message. */
+struct gam_module_poll_msg {
+ uint8_t mode;
+ uint8_t id;
+};
+
+/* Electric Air Module (EAM) constants. */
+#define EAM_SENSOR_ID 0x8e
+#define EAM_SENSOR_TEXT_ID 0xe0
+
+/* The Electric Air Module message. */
+struct eam_module_msg {
+ uint8_t start; /**< Start byte */
+ uint8_t eam_sensor_id; /**< EAM sensor */
+ uint8_t warning;
+ uint8_t sensor_text_id;
+ uint8_t alarm_inverse1;
+ uint8_t alarm_inverse2;
+ uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
+ uint8_t cell2_L;
+ uint8_t cell3_L;
+ uint8_t cell4_L;
+ uint8_t cell5_L;
+ uint8_t cell6_L;
+ uint8_t cell7_L;
+ uint8_t cell1_H;
+ uint8_t cell2_H;
+ uint8_t cell3_H;
+ uint8_t cell4_H;
+ uint8_t cell5_H;
+ uint8_t cell6_H;
+ uint8_t cell7_H;
+ uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */
+ uint8_t batt1_voltage_H;
+ uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */
+ uint8_t batt2_voltage_H;
+ uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
+ uint8_t temperature2;
+ uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
+ uint8_t altitude_H;
+ uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
+ uint8_t current_H;
+ uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
+ uint8_t main_voltage_H;
+ uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */
+ uint8_t battery_capacity_H;
+ uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
+ uint8_t climbrate_H;
+ uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
+ uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
+ uint8_t rpm_H;
+ uint8_t electric_min; /**< Flight time in minutes. */
+ uint8_t electric_sec; /**< Flight time in seconds. */
+ uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
+ uint8_t speed_H;
+ uint8_t stop; /**< Stop byte */
+ uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
+};
+
+
+/* General Air Module (GAM) constants. */
+#define GAM_SENSOR_ID 0x8d
+#define GAM_SENSOR_TEXT_ID 0xd0
+
+struct gam_module_msg {
+ uint8_t start; /**< Start byte */
+ uint8_t gam_sensor_id; /**< GAM sensor id */
+ uint8_t warning_beeps;
+ uint8_t sensor_text_id;
+ uint8_t alarm_invers1;
+ uint8_t alarm_invers2;
+ uint8_t cell1; /**< Lipo cell voltages. Not supported. */
+ uint8_t cell2;
+ uint8_t cell3;
+ uint8_t cell4;
+ uint8_t cell5;
+ uint8_t cell6;
+ uint8_t batt1_L; /**< Battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V */
+ uint8_t batt1_H;
+ uint8_t batt2_L; /**< Battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V */
+ uint8_t batt2_H;
+ uint8_t temperature1; /**< Temperature 1. offset of 20. a value of 20 = 0°C */
+ uint8_t temperature2; /**< Temperature 2. offset of 20. a value of 20 = 0°C */
+ uint8_t fuel_procent; /**< Fuel capacity in %. Values 0 - 100 */
+ /**< Graphical display ranges: 0 25% 50% 75% 100% */
+ uint8_t fuel_ml_L; /**< Fuel in ml scale. Full = 65535 */
+ uint8_t fuel_ml_H;
+ uint8_t rpm_L; /**< RPM in 10 RPM steps. 300 = 3000rpm */
+ uint8_t rpm_H;
+ uint8_t altitude_L; /**< Altitude in meters. offset of 500, 500 = 0m */
+ uint8_t altitude_H;
+ uint8_t climbrate_L; /**< Climb rate in 0.01m/s. Value of 30000 = 0.00 m/s */
+ uint8_t climbrate_H;
+ uint8_t climbrate3s; /**< Climb rate in m/3sec. Value of 120 = 0m/3sec */
+ uint8_t current_L; /**< Current in 0.1A steps */
+ uint8_t current_H;
+ uint8_t main_voltage_L; /**< Main power voltage using 0.1V steps */
+ uint8_t main_voltage_H;
+ uint8_t batt_cap_L; /**< Used battery capacity in 10mAh steps */
+ uint8_t batt_cap_H;
+ uint8_t speed_L; /**< Speed in km/h */
+ uint8_t speed_H;
+ uint8_t min_cell_volt; /**< Minimum cell voltage in 2mV steps. 124 = 2,48V */
+ uint8_t min_cell_volt_num; /**< Number of the cell with the lowest voltage */
+ uint8_t rpm2_L; /**< RPM in 10 RPM steps. 300 = 3000rpm */
+ uint8_t rpm2_H;
+ uint8_t general_error_number; /**< Voice error == 12. TODO: more docu */
+ uint8_t pressure; /**< Pressure up to 16bar. 0,1bar scale. 20 = 2bar */
+ uint8_t version;
+ uint8_t stop; /**< Stop byte */
+ uint8_t checksum; /**< Lower 8-bits of all bytes summed */
+};
+
+/* GPS sensor constants. */
+#define GPS_SENSOR_ID 0x8a
+#define GPS_SENSOR_TEXT_ID 0xa0
+
+/**
+ * The GPS sensor message
+ * Struct based on: https://code.google.com/p/diy-hott-gps/downloads
+ */
+struct gps_module_msg {
+ uint8_t start; /**< Start byte */
+ uint8_t sensor_id; /**< GPS sensor ID*/
+ uint8_t warning; /**< 0…= warning beeps */
+ uint8_t sensor_text_id; /**< GPS Sensor text mode ID */
+ uint8_t alarm_inverse1; /**< 01 inverse status */
+ uint8_t alarm_inverse2; /**< 00 inverse status status 1 = no GPS Signal */
+ uint8_t flight_direction; /**< 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */
+ uint8_t gps_speed_L; /**< 8 = /GPS speed low byte 8km/h */
+ uint8_t gps_speed_H; /**< 0 = /GPS speed high byte */
+
+ uint8_t latitude_ns; /**< 000 = N = 48°39’988 */
+ uint8_t latitude_min_L; /**< 231 0xE7 = 0x12E7 = 4839 */
+ uint8_t latitude_min_H; /**< 018 18 = 0x12 */
+ uint8_t latitude_sec_L; /**< 171 220 = 0xDC = 0x03DC =0988 */
+ uint8_t latitude_sec_H; /**< 016 3 = 0x03 */
+
+ uint8_t longitude_ew; /**< 000 = E= 9° 25’9360 */
+ uint8_t longitude_min_L; /**< 150 157 = 0x9D = 0x039D = 0925 */
+ uint8_t longitude_min_H; /**< 003 3 = 0x03 */
+ uint8_t longitude_sec_L; /**< 056 144 = 0x90 0x2490 = 9360 */
+ uint8_t longitude_sec_H; /**< 004 36 = 0x24 */
+
+ uint8_t distance_L; /**< 027 123 = /distance low byte 6 = 6 m */
+ uint8_t distance_H; /**< 036 35 = /distance high byte */
+ uint8_t altitude_L; /**< 243 244 = /Altitude low byte 500 = 0m */
+ uint8_t altitude_H; /**< 001 1 = /Altitude high byte */
+ uint8_t resolution_L; /**< 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */
+ uint8_t resolution_H; /**< 117 = High Byte m/s resolution 0.01m */
+ uint8_t unknown1; /**< 120 = 0m/3s */
+ uint8_t gps_num_sat; /**< GPS.Satellites (number of satelites) (1 byte) */
+ uint8_t gps_fix_char; /**< GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */
+ uint8_t home_direction; /**< HomeDirection (direction from starting point to Model position) (1 byte) */
+ uint8_t angle_x_direction; /**< angle x-direction (1 byte) */
+ uint8_t angle_y_direction; /**< angle y-direction (1 byte) */
+ uint8_t angle_z_direction; /**< angle z-direction (1 byte) */
+ uint8_t gyro_x_L; /**< gyro x low byte (2 bytes) */
+ uint8_t gyro_x_H; /**< gyro x high byte */
+ uint8_t gyro_y_L; /**< gyro y low byte (2 bytes) */
+ uint8_t gyro_y_H; /**< gyro y high byte */
+ uint8_t gyro_z_L; /**< gyro z low byte (2 bytes) */
+ uint8_t gyro_z_H; /**< gyro z high byte */
+ uint8_t vibration; /**< vibration (1 bytes) */
+ uint8_t ascii4; /**< 00 ASCII Free Character [4] */
+ uint8_t ascii5; /**< 00 ASCII Free Character [5] */
+ uint8_t gps_fix; /**< 00 ASCII Free Character [6], we use it for GPS FIX */
+ uint8_t version;
+ uint8_t stop; /**< Stop byte */
+ uint8_t checksum; /**< Lower 8-bits of all bytes summed */
+};
+
+// The maximum size of a message.
+#define MAX_MESSAGE_BUFFER_SIZE 45
+
+void init_sub_messages(void);
+void init_pub_messages(void);
+void build_gam_request(uint8_t *buffer, size_t *size);
+void publish_gam_message(const uint8_t *buffer);
+void build_eam_response(uint8_t *buffer, size_t *size);
+void build_gam_response(uint8_t *buffer, size_t *size);
+void build_gps_response(uint8_t *buffer, size_t *size);
+float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
+
+
+#endif /* MESSAGES_H_ */
diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c
deleted file mode 100644
index f0f32d244..000000000
--- a/src/drivers/hott_telemetry/messages.c
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Simon Wilks <sjwilks@gmail.com>
- *
- * 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 messages.c
- * @author Simon Wilks <sjwilks@gmail.com>
- */
-
-#include "messages.h"
-
-#include <string.h>
-#include <systemlib/systemlib.h>
-#include <unistd.h>
-#include <uORB/topics/airspeed.h>
-#include <uORB/topics/battery_status.h>
-#include <uORB/topics/sensor_combined.h>
-
-static int airspeed_sub = -1;
-static int battery_sub = -1;
-static int sensor_sub = -1;
-
-void messages_init(void)
-{
- battery_sub = orb_subscribe(ORB_ID(battery_status));
- sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- airspeed_sub = orb_subscribe(ORB_ID(airspeed));
-}
-
-void build_eam_response(uint8_t *buffer, int *size)
-{
- /* get a local copy of the current sensor values */
- struct sensor_combined_s raw;
- memset(&raw, 0, sizeof(raw));
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
-
- /* get a local copy of the battery data */
- struct battery_status_s battery;
- memset(&battery, 0, sizeof(battery));
- orb_copy(ORB_ID(battery_status), battery_sub, &battery);
-
- struct eam_module_msg msg;
- *size = sizeof(msg);
- memset(&msg, 0, *size);
-
- msg.start = START_BYTE;
- msg.eam_sensor_id = ELECTRIC_AIR_MODULE;
- msg.sensor_id = EAM_SENSOR_ID;
- msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20);
- msg.temperature2 = TEMP_ZERO_CELSIUS;
- msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10);
-
- uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500);
- msg.altitude_L = (uint8_t)alt & 0xff;
- msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
-
- /* get a local copy of the current sensor values */
- struct airspeed_s airspeed;
- memset(&airspeed, 0, sizeof(airspeed));
- orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
-
- uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6);
- msg.speed_L = (uint8_t)speed & 0xff;
- msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
-
- msg.stop = STOP_BYTE;
-
- memcpy(buffer, &msg, *size);
-} \ No newline at end of file
diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h
deleted file mode 100644
index dd38075fa..000000000
--- a/src/drivers/hott_telemetry/messages.h
+++ /dev/null
@@ -1,124 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Simon Wilks <sjwilks@gmail.com>
- *
- * 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 messages.h
- * @author Simon Wilks <sjwilks@gmail.com>
- *
- * Graupner HoTT Telemetry message generation.
- *
- */
-#ifndef MESSAGES_H_
-#define MESSAGES_H
-
-#include <stdlib.h>
-
-/* The buffer size used to store messages. This must be at least as big as the number of
- * fields in the largest message struct.
- */
-#define MESSAGE_BUFFER_SIZE 50
-
-/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request.
- * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting
- * the message after the read which takes some milliseconds.
- */
-#define POST_READ_DELAY_IN_USECS 4000
-/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower
- * values can be used in practise though.
- */
-#define POST_WRITE_DELAY_IN_USECS 2000
-
-// Protocol constants.
-#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request.
-#define START_BYTE 0x7c
-#define STOP_BYTE 0x7d
-#define TEMP_ZERO_CELSIUS 0x14
-
-/* Electric Air Module (EAM) constants. */
-#define ELECTRIC_AIR_MODULE 0x8e
-#define EAM_SENSOR_ID 0xe0
-
-/* The Electric Air Module message. */
-struct eam_module_msg {
- uint8_t start; /**< Start byte */
- uint8_t eam_sensor_id; /**< EAM sensor ID */
- uint8_t warning;
- uint8_t sensor_id; /**< Sensor ID, why different? */
- uint8_t alarm_inverse1;
- uint8_t alarm_inverse2;
- uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */
- uint8_t cell2_L;
- uint8_t cell3_L;
- uint8_t cell4_L;
- uint8_t cell5_L;
- uint8_t cell6_L;
- uint8_t cell7_L;
- uint8_t cell1_H;
- uint8_t cell2_H;
- uint8_t cell3_H;
- uint8_t cell4_H;
- uint8_t cell5_H;
- uint8_t cell6_H;
- uint8_t cell7_H;
- uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */
- uint8_t batt1_voltage_H;
- uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */
- uint8_t batt2_voltage_H;
- uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */
- uint8_t temperature2;
- uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */
- uint8_t altitude_H;
- uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */
- uint8_t current_H;
- uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */
- uint8_t main_voltage_H;
- uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */
- uint8_t battery_capacity_H;
- uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */
- uint8_t climbrate_H;
- uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */
- uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */
- uint8_t rpm_H;
- uint8_t electric_min; /**< Flight time in minutes. */
- uint8_t electric_sec; /**< Flight time in seconds. */
- uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */
- uint8_t speed_H;
- uint8_t stop; /**< Stop byte */
- uint8_t checksum; /**< Lower 8-bits of all bytes summed. */
-};
-
-void messages_init(void);
-void build_eam_response(uint8_t *buffer, int *size);
-
-#endif /* MESSAGES_H_ */
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 98098c83b..90c3db9ae 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -59,11 +59,14 @@
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-
#include <drivers/device/spi.h>
#include <drivers/drv_gyro.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <board_config.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#define L3GD20_DEVICE_PATH "/dev/l3gd20"
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -71,6 +74,12 @@
#endif
static const int ERROR = -1;
+/* Orientation on board */
+#define SENSOR_BOARD_ROTATION_000_DEG 0
+#define SENSOR_BOARD_ROTATION_090_DEG 1
+#define SENSOR_BOARD_ROTATION_180_DEG 2
+#define SENSOR_BOARD_ROTATION_270_DEG 3
+
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
@@ -78,15 +87,24 @@ static const int ERROR = -1;
/* register addresses */
#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM_H 0xD7
#define WHO_I_AM 0xD4
#define ADDR_CTRL_REG1 0x20
#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
/* keep lowpass low to avoid noise issues */
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
-#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
-#define RATE_380HZ_LP_30HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
-#define RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
+#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
+#define RATE_190HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4))
+#define RATE_190HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
+#define RATE_380HZ_LP_20HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+#define RATE_380HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4))
+#define RATE_380HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+#define RATE_380HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
+#define RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
+#define RATE_760HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4))
+#define RATE_760HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4))
+#define RATE_760HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
#define ADDR_CTRL_REG2 0x21
#define ADDR_CTRL_REG3 0x22
@@ -147,6 +165,10 @@ static const int ERROR = -1;
#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
+#define L3GD20_DEFAULT_RATE 760
+#define L3GD20_DEFAULT_RANGE_DPS 2000
+#define L3GD20_DEFAULT_FILTER_FREQ 30
+
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -172,21 +194,27 @@ private:
struct hrt_call _call;
unsigned _call_interval;
-
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- struct gyro_report *_reports;
+
+ RingBuffer *_reports;
struct gyro_scale _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;
orb_advert_t _gyro_topic;
+ int _class_instance;
unsigned _current_rate;
- unsigned _current_range;
+ unsigned _orientation;
+
+ unsigned _read;
perf_counter_t _sample_perf;
+ perf_counter_t _reschedules;
+ perf_counter_t _errors;
+
+ math::LowPassFilter2p _gyro_filter_x;
+ math::LowPassFilter2p _gyro_filter_y;
+ math::LowPassFilter2p _gyro_filter_z;
/**
* Start automatic measurement.
@@ -199,6 +227,16 @@ private:
void stop();
/**
+ * Reset the driver
+ */
+ void reset();
+
+ /**
+ * disable I2C on the chip
+ */
+ void disable_i2c();
+
+ /**
* Static trampoline from the hrt_call context; because we don't have a
* generic hrt wrapper yet.
*
@@ -260,25 +298,40 @@ private:
* @return OK if the value can be supported.
*/
int set_samplerate(unsigned frequency);
-};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
+ /**
+ * Set the lowpass filter of the driver
+ *
+ * @param samplerate The current samplerate
+ * @param frequency The cutoff frequency for the lowpass filter
+ */
+ void set_driver_lowpass_filter(float samplerate, float bandwidth);
+ /**
+ * Self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int self_test();
+};
L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
- SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 8000000),
+ SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */),
_call_interval(0),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
+ _class_instance(-1),
_current_rate(0),
- _current_range(0),
- _sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read"))
+ _orientation(SENSOR_BOARD_ROTATION_270_DEG),
+ _read(0),
+ _sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
+ _reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
+ _errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
+ _gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
+ _gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
+ _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ)
{
// enable debug() calls
_debug_enabled = true;
@@ -299,10 +352,15 @@ L3GD20::~L3GD20()
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
+
+ if (_class_instance != -1)
+ unregister_class_devname(GYRO_DEVICE_PATH, _class_instance);
/* delete the perf counter */
perf_free(_sample_perf);
+ perf_free(_reschedules);
+ perf_free(_errors);
}
int
@@ -315,29 +373,29 @@ L3GD20::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _oldest_report = _next_report = 0;
- _reports = new struct gyro_report[_num_reports];
+ _reports = new RingBuffer(2, sizeof(gyro_report));
if (_reports == nullptr)
goto out;
- /* advertise sensor topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_reports[0]);
+ _class_instance = register_class_devname(GYRO_DEVICE_PATH);
- /* set default configuration */
- write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
- write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
- write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
- write_reg(ADDR_CTRL_REG4, REG4_BDU);
- write_reg(ADDR_CTRL_REG5, 0);
+ reset();
+
+ measure();
- write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
- write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
- set_range(500); /* default to 500dps */
- set_samplerate(0); /* max sample rate */
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _reports->get(&grp);
+
+ _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+
+ if (_gyro_topic < 0)
+ debug("failed to create sensor_gyro publication");
+
+ }
ret = OK;
out:
@@ -350,8 +408,29 @@ L3GD20::probe()
/* read dummy value to void to clear SPI statemachine on sensor */
(void)read_reg(ADDR_WHO_AM_I);
- /* verify that the device is attached and functioning */
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM)
+ bool success = false;
+
+ /* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ _orientation = SENSOR_BOARD_ROTATION_270_DEG;
+ #elif CONFIG_ARCH_BOARD_PX4FMU_V2
+ _orientation = SENSOR_BOARD_ROTATION_270_DEG;
+ #else
+ #error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+ #endif
+
+ success = true;
+ }
+
+
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_H) {
+ _orientation = SENSOR_BOARD_ROTATION_180_DEG;
+ success = true;
+ }
+
+ if (success)
return OK;
return -EIO;
@@ -361,6 +440,7 @@ ssize_t
L3GD20::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct gyro_report);
+ struct gyro_report *gbuf = reinterpret_cast<struct gyro_report *>(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -376,10 +456,9 @@ L3GD20::read(struct file *filp, char *buffer, size_t buflen)
* we are careful to avoid racing with it.
*/
while (count--) {
- if (_oldest_report != _next_report) {
- memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
- ret += sizeof(_reports[0]);
- INCREMENT(_oldest_report, _num_reports);
+ if (_reports->get(gbuf)) {
+ ret += sizeof(*gbuf);
+ gbuf++;
}
}
@@ -388,12 +467,13 @@ L3GD20::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement */
- _oldest_report = _next_report = 0;
+ _reports->flush();
measure();
/* measurement will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(gbuf)) {
+ ret = sizeof(*gbuf);
+ }
return ret;
}
@@ -422,8 +502,7 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
- /* With internal low pass filters enabled, 250 Hz is sufficient */
- return ioctl(filp, SENSORIOCSPOLLRATE, 250);
+ return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
default: {
@@ -441,6 +520,11 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* XXX this is a bit shady, but no other way to adjust... */
_call.period = _call_interval = ticks;
+ /* adjust filters */
+ float cutoff_freq_hz = _gyro_filter_x.get_cutoff_freq();
+ float sample_rate = 1.0e6f/ticks;
+ set_driver_lowpass_filter(sample_rate, cutoff_freq_hz);
+
/* if we need to start the poll state machine, do it */
if (want_start)
start();
@@ -457,35 +541,26 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
case SENSORIOCSQUEUEDEPTH: {
- /* account for 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 gyro_report *buf = new struct gyro_report[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;
+ /* 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 _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
- /* XXX implement */
- return -EINVAL;
+ reset();
+ return OK;
case GYROIOCSSAMPLERATE:
return set_samplerate(arg);
@@ -493,10 +568,16 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
case GYROIOCGSAMPLERATE:
return _current_rate;
- case GYROIOCSLOWPASS:
+ case GYROIOCSLOWPASS: {
+ float cutoff_freq_hz = arg;
+ float sample_rate = 1.0e6f / _call_interval;
+ set_driver_lowpass_filter(sample_rate, cutoff_freq_hz);
+
+ return OK;
+ }
+
case GYROIOCGLOWPASS:
- /* XXX not implemented due to wacky interaction with samplerate */
- return -EINVAL;
+ return _gyro_filter_x.get_cutoff_freq();
case GYROIOCSSCALE:
/* copy scale in */
@@ -509,10 +590,15 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case GYROIOCSRANGE:
+ /* arg should be in dps */
return set_range(arg);
case GYROIOCGRANGE:
- return _current_range;
+ /* convert to dps and round */
+ return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
+
+ case GYROIOCSELFTEST:
+ return self_test();
default:
/* give it to the superclass */
@@ -526,6 +612,7 @@ L3GD20::read_reg(unsigned reg)
uint8_t cmd[2];
cmd[0] = reg | DIR_READ;
+ cmd[1] = 0;
transfer(cmd, cmd, sizeof(cmd));
@@ -558,28 +645,33 @@ int
L3GD20::set_range(unsigned max_dps)
{
uint8_t bits = REG4_BDU;
+ float new_range_scale_dps_digit;
+ float new_range;
- if (max_dps == 0)
+ if (max_dps == 0) {
max_dps = 2000;
-
+ }
if (max_dps <= 250) {
- _current_range = 250;
+ new_range = 250;
bits |= RANGE_250DPS;
+ new_range_scale_dps_digit = 8.75e-3f;
} else if (max_dps <= 500) {
- _current_range = 500;
+ new_range = 500;
bits |= RANGE_500DPS;
+ new_range_scale_dps_digit = 17.5e-3f;
} else if (max_dps <= 2000) {
- _current_range = 2000;
+ new_range = 2000;
bits |= RANGE_2000DPS;
+ new_range_scale_dps_digit = 70e-3f;
} else {
return -EINVAL;
}
- _gyro_range_rad_s = _current_range / 180.0f * M_PI_F;
- _gyro_range_scale = _gyro_range_rad_s / 32768.0f;
+ _gyro_range_rad_s = new_range / 180.0f * M_PI_F;
+ _gyro_range_scale = new_range_scale_dps_digit / 180.0f * M_PI_F;
write_reg(ADDR_CTRL_REG4, bits);
return OK;
@@ -593,22 +685,22 @@ L3GD20::set_samplerate(unsigned frequency)
if (frequency == 0)
frequency = 760;
- if (frequency <= 95) {
+ /* use limits good for H or non-H models */
+ if (frequency <= 100) {
_current_rate = 95;
bits |= RATE_95HZ_LP_25HZ;
- } else if (frequency <= 190) {
+ } else if (frequency <= 200) {
_current_rate = 190;
- bits |= RATE_190HZ_LP_25HZ;
+ bits |= RATE_190HZ_LP_50HZ;
- } else if (frequency <= 380) {
+ } else if (frequency <= 400) {
_current_rate = 380;
- bits |= RATE_380HZ_LP_30HZ;
+ bits |= RATE_380HZ_LP_50HZ;
- } else if (frequency <= 760) {
+ } else if (frequency <= 800) {
_current_rate = 760;
- bits |= RATE_760HZ_LP_30HZ;
-
+ bits |= RATE_760HZ_LP_50HZ;
} else {
return -EINVAL;
}
@@ -619,13 +711,21 @@ L3GD20::set_samplerate(unsigned frequency)
}
void
+L3GD20::set_driver_lowpass_filter(float samplerate, float bandwidth)
+{
+ _gyro_filter_x.set_cutoff_frequency(samplerate, bandwidth);
+ _gyro_filter_y.set_cutoff_frequency(samplerate, bandwidth);
+ _gyro_filter_z.set_cutoff_frequency(samplerate, bandwidth);
+}
+
+void
L3GD20::start()
{
/* make sure we are stopped first */
stop();
/* reset the report ring */
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&L3GD20::measure_trampoline, this);
@@ -638,6 +738,48 @@ L3GD20::stop()
}
void
+L3GD20::disable_i2c(void)
+{
+ uint8_t retries = 10;
+ while (retries--) {
+ // add retries
+ uint8_t a = read_reg(0x05);
+ write_reg(0x05, (0x20 | a));
+ if (read_reg(0x05) == (a | 0x20)) {
+ return;
+ }
+ }
+ debug("FAILED TO DISABLE I2C");
+}
+
+void
+L3GD20::reset()
+{
+ // ensure the chip doesn't interpret any other bus traffic as I2C
+ disable_i2c();
+
+ /* set default configuration */
+ write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+ write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
+ write_reg(ADDR_CTRL_REG3, 0x08); /* DRDY enable */
+ write_reg(ADDR_CTRL_REG4, REG4_BDU);
+ write_reg(ADDR_CTRL_REG5, 0);
+
+ write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
+
+ /* disable FIFO. This makes things simpler and ensures we
+ * aren't getting stale data. It means we must run the hrt
+ * callback fast enough to not miss data. */
+ write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
+
+ set_samplerate(0); // 760Hz
+ set_range(L3GD20_DEFAULT_RANGE_DPS);
+ set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
+
+ _read = 0;
+}
+
+void
L3GD20::measure_trampoline(void *arg)
{
L3GD20 *dev = (L3GD20 *)arg;
@@ -646,9 +788,26 @@ L3GD20::measure_trampoline(void *arg)
dev->measure();
}
+#ifdef GPIO_EXTI_GYRO_DRDY
+# define L3GD20_USE_DRDY 1
+#else
+# define L3GD20_USE_DRDY 0
+#endif
+
void
L3GD20::measure()
{
+#if L3GD20_USE_DRDY
+ // if the gyro doesn't have any data ready then re-schedule
+ // for 100 microseconds later. This ensures we don't double
+ // read a value and then miss the next value
+ if (stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
+ perf_count(_reschedules);
+ hrt_call_delay(&_call, 100);
+ return;
+ }
+#endif
+
/* status register and data as read back from the device */
#pragma pack(push, 1)
struct {
@@ -661,15 +820,26 @@ L3GD20::measure()
} raw_report;
#pragma pack(pop)
- gyro_report *report = &_reports[_next_report];
+ gyro_report report;
/* start the performance counter */
perf_begin(_sample_perf);
/* fetch data from the sensor */
+ memset(&raw_report, 0, sizeof(raw_report));
raw_report.cmd = ADDR_OUT_TEMP | DIR_READ | ADDR_INCREMENT;
transfer((uint8_t *)&raw_report, (uint8_t *)&raw_report, sizeof(raw_report));
+#if L3GD20_USE_DRDY
+ if ((raw_report.status & 0xF) != 0xF) {
+ /*
+ we waited for DRDY, but did not see DRDY on all axes
+ when we captured. That means a transfer error of some sort
+ */
+ perf_count(_errors);
+ return;
+ }
+#endif
/*
* 1) Scale raw value to SI units using scaling from datasheet.
* 2) Subtract static offset (in SI units)
@@ -684,31 +854,61 @@ L3GD20::measure()
* the offset is 74 from the origin and subtracting
* 74 from all measurements centers them around zero.
*/
- report->timestamp = hrt_absolute_time();
+ report.timestamp = hrt_absolute_time();
+ report.error_count = 0; // not recorded
- /* swap x and y and negate y */
- report->x_raw = raw_report.y;
- report->y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
- report->z_raw = raw_report.z;
+ switch (_orientation) {
+
+ case SENSOR_BOARD_ROTATION_000_DEG:
+ /* keep axes in place */
+ report.x_raw = raw_report.x;
+ report.y_raw = raw_report.y;
+ break;
+
+ case SENSOR_BOARD_ROTATION_090_DEG:
+ /* swap x and y */
+ report.x_raw = raw_report.y;
+ report.y_raw = raw_report.x;
+ break;
+
+ case SENSOR_BOARD_ROTATION_180_DEG:
+ /* swap x and y and negate both */
+ report.x_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
+ report.y_raw = ((raw_report.y == -32768) ? 32767 : -raw_report.y);
+ break;
+
+ case SENSOR_BOARD_ROTATION_270_DEG:
+ /* swap x and y and negate y */
+ report.x_raw = raw_report.y;
+ report.y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
+ break;
+ }
+
+ report.z_raw = raw_report.z;
+
+ report.x = ((report.x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
+ report.y = ((report.y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
+ report.z = ((report.z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
- report->x = ((report->x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
- report->y = ((report->y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
- report->z = ((report->z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
- report->scaling = _gyro_range_scale;
- report->range_rad_s = _gyro_range_rad_s;
+ report.x = _gyro_filter_x.apply(report.x);
+ report.y = _gyro_filter_y.apply(report.y);
+ report.z = _gyro_filter_z.apply(report.z);
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
+ report.scaling = _gyro_range_scale;
+ report.range_rad_s = _gyro_range_rad_s;
- /* if we are running up against the oldest report, fix it */
- if (_next_report == _oldest_report)
- INCREMENT(_oldest_report, _num_reports);
+ _reports->force(&report);
/* notify anyone waiting for data */
poll_notify(POLLIN);
/* publish for subscribers */
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, report);
+ if (_gyro_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report);
+ }
+
+ _read++;
/* stop the perf counter */
perf_end(_sample_perf);
@@ -717,9 +917,33 @@ L3GD20::measure()
void
L3GD20::print_info()
{
+ printf("gyro reads: %u\n", _read);
perf_print_counter(_sample_perf);
- printf("report queue: %u (%u/%u @ %p)\n",
- _num_reports, _oldest_report, _next_report, _reports);
+ perf_print_counter(_reschedules);
+ perf_print_counter(_errors);
+ _reports->print_info("report queue");
+}
+
+int
+L3GD20::self_test()
+{
+ /* evaluate gyro offsets, complain if offset -> zero or larger than 6 dps */
+ if (fabsf(_gyro_scale.x_offset) > 0.1f || fabsf(_gyro_scale.x_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f)
+ return 1;
+
+ if (fabsf(_gyro_scale.y_offset) > 0.1f || fabsf(_gyro_scale.y_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f)
+ return 1;
+
+ if (fabsf(_gyro_scale.z_offset) > 0.1f || fabsf(_gyro_scale.z_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f)
+ return 1;
+
+ return 0;
}
/**
@@ -744,10 +968,10 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(1 /* XXX magic number */, GYRO_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
if (g_dev == nullptr)
goto fail;
@@ -756,7 +980,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(GYRO_DEVICE_PATH, O_RDONLY);
+ fd = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd < 0)
goto fail;
@@ -764,6 +988,8 @@ start()
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
goto fail;
+ close(fd);
+
exit(0);
fail:
@@ -788,10 +1014,10 @@ test()
ssize_t sz;
/* get the driver */
- fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
+ fd_gyro = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd_gyro < 0)
- err(1, "%s open failed", GYRO_DEVICE_PATH);
+ err(1, "%s open failed", L3GD20_DEVICE_PATH);
/* reset to manual polling */
if (ioctl(fd_gyro, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@@ -812,6 +1038,8 @@ test()
warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
(int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
+ close(fd_gyro);
+
/* XXX add poll-rate tests here too */
reset();
@@ -824,7 +1052,7 @@ test()
void
reset()
{
- int fd = open(GYRO_DEVICE_PATH, O_RDONLY);
+ int fd = open(L3GD20_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -833,7 +1061,9 @@ reset()
err(1, "driver reset failed");
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
- err(1, "driver poll restart failed");
+ err(1, "accel pollrate reset failed");
+
+ close(fd);
exit(0);
}
diff --git a/src/drivers/led/led.cpp b/src/drivers/led/led.cpp
index 04b565358..a37eaca53 100644
--- a/src/drivers/led/led.cpp
+++ b/src/drivers/led/led.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -52,6 +52,7 @@ __BEGIN_DECLS
extern void led_init();
extern void led_on(int led);
extern void led_off(int led);
+extern void led_toggle(int led);
__END_DECLS
class LED : device::CDev
@@ -98,6 +99,11 @@ LED::ioctl(struct file *filp, int cmd, unsigned long arg)
led_off(arg);
break;
+ case LED_TOGGLE:
+ led_toggle(arg);
+ break;
+
+
default:
result = CDev::ioctl(filp, cmd, arg);
}
@@ -110,11 +116,11 @@ LED *gLED;
}
void
-drv_led_start()
+drv_led_start(void)
{
if (gLED == nullptr) {
gLED = new LED;
if (gLED != nullptr)
gLED->init();
}
-} \ No newline at end of file
+}
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
new file mode 100644
index 000000000..4dee7649b
--- /dev/null
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -0,0 +1,2036 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 lsm303d.cpp
+ * Driver for the ST LSM303D MEMS accelerometer / magnetometer connected via SPI.
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stddef.h>
+#include <stdlib.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 <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/clock.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/device/spi.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_mag.h>
+#include <drivers/device/ringbuffer.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include <board_config.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+/* SPI protocol address bits */
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define LSM303D_DEVICE_PATH_ACCEL "/dev/lsm303d_accel"
+#define LSM303D_DEVICE_PATH_MAG "/dev/lsm303d_mag"
+
+/* register addresses: A: accel, M: mag, T: temp */
+#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM 0x49
+
+#define ADDR_OUT_TEMP_L 0x05
+#define ADDR_OUT_TEMP_H 0x06
+#define ADDR_STATUS_M 0x07
+#define ADDR_OUT_X_L_M 0x08
+#define ADDR_OUT_X_H_M 0x09
+#define ADDR_OUT_Y_L_M 0x0A
+#define ADDR_OUT_Y_H_M 0x0B
+#define ADDR_OUT_Z_L_M 0x0C
+#define ADDR_OUT_Z_H_M 0x0D
+
+#define ADDR_INT_CTRL_M 0x12
+#define ADDR_INT_SRC_M 0x13
+#define ADDR_REFERENCE_X 0x1c
+#define ADDR_REFERENCE_Y 0x1d
+#define ADDR_REFERENCE_Z 0x1e
+
+#define ADDR_STATUS_A 0x27
+#define ADDR_OUT_X_L_A 0x28
+#define ADDR_OUT_X_H_A 0x29
+#define ADDR_OUT_Y_L_A 0x2A
+#define ADDR_OUT_Y_H_A 0x2B
+#define ADDR_OUT_Z_L_A 0x2C
+#define ADDR_OUT_Z_H_A 0x2D
+
+#define ADDR_CTRL_REG0 0x1F
+#define ADDR_CTRL_REG1 0x20
+#define ADDR_CTRL_REG2 0x21
+#define ADDR_CTRL_REG3 0x22
+#define ADDR_CTRL_REG4 0x23
+#define ADDR_CTRL_REG5 0x24
+#define ADDR_CTRL_REG6 0x25
+#define ADDR_CTRL_REG7 0x26
+
+#define ADDR_FIFO_CTRL 0x2e
+#define ADDR_FIFO_SRC 0x2f
+
+#define ADDR_IG_CFG1 0x30
+#define ADDR_IG_SRC1 0x31
+#define ADDR_IG_THS1 0x32
+#define ADDR_IG_DUR1 0x33
+#define ADDR_IG_CFG2 0x34
+#define ADDR_IG_SRC2 0x35
+#define ADDR_IG_THS2 0x36
+#define ADDR_IG_DUR2 0x37
+#define ADDR_CLICK_CFG 0x38
+#define ADDR_CLICK_SRC 0x39
+#define ADDR_CLICK_THS 0x3a
+#define ADDR_TIME_LIMIT 0x3b
+#define ADDR_TIME_LATENCY 0x3c
+#define ADDR_TIME_WINDOW 0x3d
+#define ADDR_ACT_THS 0x3e
+#define ADDR_ACT_DUR 0x3f
+
+#define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
+#define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
+#define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
+#define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
+#define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
+#define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+
+#define REG1_BDU_UPDATE (1<<3)
+#define REG1_Z_ENABLE_A (1<<2)
+#define REG1_Y_ENABLE_A (1<<1)
+#define REG1_X_ENABLE_A (1<<0)
+
+#define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
+#define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
+#define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
+#define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
+#define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
+
+#define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
+#define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
+#define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
+#define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
+#define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
+#define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
+
+#define REG5_ENABLE_T (1<<7)
+
+#define REG5_RES_HIGH_M ((1<<6) | (1<<5))
+#define REG5_RES_LOW_M ((0<<6) | (0<<5))
+
+#define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
+#define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
+#define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
+#define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
+#define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
+#define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
+#define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
+#define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
+
+#define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
+#define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
+#define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
+#define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
+#define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
+
+#define REG7_CONT_MODE_M ((0<<1) | (0<<0))
+
+
+#define INT_CTRL_M 0x12
+#define INT_SRC_M 0x13
+
+/* default values for this device */
+#define LSM303D_ACCEL_DEFAULT_RANGE_G 8
+#define LSM303D_ACCEL_DEFAULT_RATE 800
+#define LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 50
+#define LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define LSM303D_MAG_DEFAULT_RANGE_GA 2
+#define LSM303D_MAG_DEFAULT_RATE 100
+
+#define LSM303D_ONE_G 9.80665f
+
+extern "C" { __EXPORT int lsm303d_main(int argc, char *argv[]); }
+
+
+class LSM303D_mag;
+
+class LSM303D : public device::SPI
+{
+public:
+ LSM303D(int bus, const char* path, spi_dev_e device);
+ virtual ~LSM303D();
+
+ 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();
+
+ /**
+ * dump register values
+ */
+ void print_registers();
+
+ /**
+ * toggle logging
+ */
+ void toggle_logging();
+
+ /**
+ * check for extreme accel values
+ */
+ void check_extremes(const accel_report *arb);
+
+protected:
+ virtual int probe();
+
+ friend class LSM303D_mag;
+
+ virtual ssize_t mag_read(struct file *filp, char *buffer, size_t buflen);
+ virtual int mag_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+private:
+
+ LSM303D_mag *_mag;
+
+ struct hrt_call _accel_call;
+ struct hrt_call _mag_call;
+
+ unsigned _call_accel_interval;
+ unsigned _call_mag_interval;
+
+ RingBuffer *_accel_reports;
+ RingBuffer *_mag_reports;
+
+ struct accel_scale _accel_scale;
+ unsigned _accel_range_m_s2;
+ float _accel_range_scale;
+ unsigned _accel_samplerate;
+ unsigned _accel_onchip_filter_bandwith;
+
+ struct mag_scale _mag_scale;
+ unsigned _mag_range_ga;
+ float _mag_range_scale;
+ unsigned _mag_samplerate;
+
+ orb_advert_t _accel_topic;
+ int _accel_class_instance;
+
+ unsigned _accel_read;
+ unsigned _mag_read;
+
+ perf_counter_t _accel_sample_perf;
+ perf_counter_t _mag_sample_perf;
+ perf_counter_t _reg1_resets;
+ perf_counter_t _reg7_resets;
+ perf_counter_t _extreme_values;
+ perf_counter_t _accel_reschedules;
+
+ math::LowPassFilter2p _accel_filter_x;
+ math::LowPassFilter2p _accel_filter_y;
+ math::LowPassFilter2p _accel_filter_z;
+
+ // expceted values of reg1 and reg7 to catch in-flight
+ // brownouts of the sensor
+ uint8_t _reg1_expected;
+ uint8_t _reg7_expected;
+
+ // accel logging
+ int _accel_log_fd;
+ bool _accel_logging_enabled;
+ uint64_t _last_extreme_us;
+ uint64_t _last_log_us;
+ uint64_t _last_log_sync_us;
+ uint64_t _last_log_reg_us;
+ uint64_t _last_log_alarm_us;
+
+ /**
+ * Start automatic measurement.
+ */
+ void start();
+
+ /**
+ * Stop automatic measurement.
+ */
+ void stop();
+
+ /**
+ * Reset chip.
+ *
+ * Resets the chip and measurements ranges, but not scale and offset.
+ */
+ void reset();
+
+ /**
+ * disable I2C on the chip
+ */
+ void disable_i2c();
+
+ /**
+ * Static trampoline from the hrt_call context; because we don't have a
+ * generic hrt wrapper yet.
+ *
+ * Called by the HRT in interrupt context at the specified rate if
+ * automatic polling is enabled.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void measure_trampoline(void *arg);
+
+ /**
+ * Static trampoline for the mag because it runs at a lower rate
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void mag_measure_trampoline(void *arg);
+
+ /**
+ * Fetch accel measurements from the sensor and update the report ring.
+ */
+ void measure();
+
+ /**
+ * Fetch mag measurements from the sensor and update the report ring.
+ */
+ void mag_measure();
+
+ /**
+ * Accel self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int accel_self_test();
+
+ /**
+ * Mag self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int mag_self_test();
+
+ /**
+ * Read a register from the LSM303D
+ *
+ * @param The register to read.
+ * @return The value that was read.
+ */
+ uint8_t read_reg(unsigned reg);
+
+ /**
+ * Write a register in the LSM303D
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_reg(unsigned reg, uint8_t value);
+
+ /**
+ * Modify a register in the LSM303D
+ *
+ * Bits are cleared before bits are set.
+ *
+ * @param reg The register to modify.
+ * @param clearbits Bits in the register to clear.
+ * @param setbits Bits in the register to set.
+ */
+ void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
+
+ /**
+ * Set the LSM303D accel measurement range.
+ *
+ * @param max_g The measurement range of the accel is in g (9.81m/s^2)
+ * Zero selects the maximum supported range.
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_range(unsigned max_g);
+
+ /**
+ * Set the LSM303D mag measurement range.
+ *
+ * @param max_ga The measurement range of the mag is in Ga
+ * Zero selects the maximum supported range.
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int mag_set_range(unsigned max_g);
+
+ /**
+ * Set the LSM303D on-chip anti-alias filter bandwith.
+ *
+ * @param bandwidth The anti-alias filter bandwidth in Hz
+ * Zero selects the highest bandwidth
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth);
+
+ /**
+ * Set the driver lowpass filter bandwidth.
+ *
+ * @param bandwidth The anti-alias filter bandwidth in Hz
+ * Zero selects the highest bandwidth
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_driver_lowpass_filter(float samplerate, float bandwidth);
+
+ /**
+ * Set the LSM303D internal accel sampling frequency.
+ *
+ * @param frequency The internal accel sampling frequency is set to not less than
+ * this value.
+ * Zero selects the maximum rate supported.
+ * @return OK if the value can be supported.
+ */
+ int accel_set_samplerate(unsigned frequency);
+
+ /**
+ * Set the LSM303D internal mag sampling frequency.
+ *
+ * @param frequency The internal mag sampling frequency is set to not less than
+ * this value.
+ * Zero selects the maximum rate supported.
+ * @return OK if the value can be supported.
+ */
+ int mag_set_samplerate(unsigned frequency);
+};
+
+/**
+ * Helper class implementing the mag driver node.
+ */
+class LSM303D_mag : public device::CDev
+{
+public:
+ LSM303D_mag(LSM303D *parent);
+ ~LSM303D_mag();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ virtual int init();
+
+protected:
+ friend class LSM303D;
+
+ void parent_poll_notify();
+private:
+ LSM303D *_parent;
+
+ orb_advert_t _mag_topic;
+ int _mag_class_instance;
+
+ void measure();
+
+ void measure_trampoline(void *arg);
+};
+
+
+LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
+ SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */),
+ _mag(new LSM303D_mag(this)),
+ _call_accel_interval(0),
+ _call_mag_interval(0),
+ _accel_reports(nullptr),
+ _mag_reports(nullptr),
+ _accel_range_m_s2(0.0f),
+ _accel_range_scale(0.0f),
+ _accel_samplerate(0),
+ _accel_onchip_filter_bandwith(0),
+ _mag_range_ga(0.0f),
+ _mag_range_scale(0.0f),
+ _mag_samplerate(0),
+ _accel_topic(-1),
+ _accel_class_instance(-1),
+ _accel_read(0),
+ _mag_read(0),
+ _accel_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d_accel_read")),
+ _mag_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d_mag_read")),
+ _reg1_resets(perf_alloc(PC_COUNT, "lsm303d_reg1_resets")),
+ _reg7_resets(perf_alloc(PC_COUNT, "lsm303d_reg7_resets")),
+ _extreme_values(perf_alloc(PC_COUNT, "lsm303d_extremes")),
+ _accel_reschedules(perf_alloc(PC_COUNT, "lsm303d_accel_resched")),
+ _accel_filter_x(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_y(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_z(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _reg1_expected(0),
+ _reg7_expected(0),
+ _accel_log_fd(-1),
+ _accel_logging_enabled(false),
+ _last_log_us(0),
+ _last_log_sync_us(0),
+ _last_log_reg_us(0),
+ _last_log_alarm_us(0)
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // default scale factors
+ _accel_scale.x_offset = 0.0f;
+ _accel_scale.x_scale = 1.0f;
+ _accel_scale.y_offset = 0.0f;
+ _accel_scale.y_scale = 1.0f;
+ _accel_scale.z_offset = 0.0f;
+ _accel_scale.z_scale = 1.0f;
+
+ _mag_scale.x_offset = 0.0f;
+ _mag_scale.x_scale = 1.0f;
+ _mag_scale.y_offset = 0.0f;
+ _mag_scale.y_scale = 1.0f;
+ _mag_scale.z_offset = 0.0f;
+ _mag_scale.z_scale = 1.0f;
+}
+
+LSM303D::~LSM303D()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_accel_reports != nullptr)
+ delete _accel_reports;
+ if (_mag_reports != nullptr)
+ delete _mag_reports;
+
+ if (_accel_class_instance != -1)
+ unregister_class_devname(ACCEL_DEVICE_PATH, _accel_class_instance);
+
+ delete _mag;
+
+ /* delete the perf counter */
+ perf_free(_accel_sample_perf);
+ perf_free(_mag_sample_perf);
+ perf_free(_reg1_resets);
+ perf_free(_reg7_resets);
+ perf_free(_extreme_values);
+ perf_free(_accel_reschedules);
+}
+
+int
+LSM303D::init()
+{
+ int ret = ERROR;
+
+ /* do SPI init (and probe) first */
+ if (SPI::init() != OK) {
+ warnx("SPI init failed");
+ goto out;
+ }
+
+ /* allocate basic report buffers */
+ _accel_reports = new RingBuffer(2, sizeof(accel_report));
+
+ if (_accel_reports == nullptr)
+ goto out;
+
+ /* advertise accel topic */
+ _mag_reports = new RingBuffer(2, sizeof(mag_report));
+
+ if (_mag_reports == nullptr)
+ goto out;
+
+ reset();
+
+ /* do CDev init for the mag device node */
+ ret = _mag->init();
+ if (ret != OK) {
+ warnx("MAG init failed");
+ goto out;
+ }
+
+ /* fill report structures */
+ measure();
+
+ if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct mag_report mrp;
+ _mag_reports->get(&mrp);
+
+ /* measurement will have generated a report, publish */
+ _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mrp);
+
+ if (_mag->_mag_topic < 0)
+ debug("failed to create sensor_mag publication");
+
+ }
+
+ _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH);
+
+ if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
+
+ /* measurement will have generated a report, publish */
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+
+ if (_accel_topic < 0)
+ debug("failed to create sensor_accel publication");
+
+ }
+
+out:
+ return ret;
+}
+
+void
+LSM303D::disable_i2c(void)
+{
+ uint8_t a = read_reg(0x02);
+ write_reg(0x02, (0x10 | a));
+ a = read_reg(0x02);
+ write_reg(0x02, (0xF7 & a));
+ a = read_reg(0x15);
+ write_reg(0x15, (0x80 | a));
+ a = read_reg(0x02);
+ write_reg(0x02, (0xE7 & a));
+}
+
+void
+LSM303D::reset()
+{
+ // ensure the chip doesn't interpret any other bus traffic as I2C
+ disable_i2c();
+
+ /* enable accel*/
+ _reg1_expected = REG1_X_ENABLE_A | REG1_Y_ENABLE_A | REG1_Z_ENABLE_A | REG1_BDU_UPDATE | REG1_RATE_800HZ_A;
+ write_reg(ADDR_CTRL_REG1, _reg1_expected);
+
+ /* enable mag */
+ _reg7_expected = REG7_CONT_MODE_M;
+ write_reg(ADDR_CTRL_REG7, _reg7_expected);
+ write_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
+ write_reg(ADDR_CTRL_REG3, 0x04); // DRDY on ACCEL on INT1
+ write_reg(ADDR_CTRL_REG4, 0x04); // DRDY on MAG on INT2
+
+ accel_set_range(LSM303D_ACCEL_DEFAULT_RANGE_G);
+ accel_set_samplerate(LSM303D_ACCEL_DEFAULT_RATE);
+ accel_set_driver_lowpass_filter((float)LSM303D_ACCEL_DEFAULT_RATE, (float)LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ);
+
+ // we setup the anti-alias on-chip filter as 50Hz. We believe
+ // this operates in the analog domain, and is critical for
+ // anti-aliasing. The 2 pole software filter is designed to
+ // operate in conjunction with this on-chip filter
+ accel_set_onchip_lowpass_filter_bandwidth(LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ);
+
+ mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
+ mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
+
+ _accel_read = 0;
+ _mag_read = 0;
+}
+
+int
+LSM303D::probe()
+{
+ /* read dummy value to void to clear SPI statemachine on sensor */
+ (void)read_reg(ADDR_WHO_AM_I);
+
+ /* verify that the device is attached and functioning */
+ bool success = (read_reg(ADDR_WHO_AM_I) == WHO_I_AM);
+
+ if (success)
+ return OK;
+
+ return -EIO;
+}
+
+#define ACCEL_LOGFILE "/fs/microsd/lsm303d.log"
+
+/**
+ check for extreme accelerometer values and log to a file on the SD card
+ */
+void
+LSM303D::check_extremes(const accel_report *arb)
+{
+ const float extreme_threshold = 30;
+ static bool boot_ok = false;
+ bool is_extreme = (fabsf(arb->x) > extreme_threshold &&
+ fabsf(arb->y) > extreme_threshold &&
+ fabsf(arb->z) > extreme_threshold);
+ if (is_extreme) {
+ perf_count(_extreme_values);
+ // force accel logging on if we see extreme values
+ _accel_logging_enabled = true;
+ } else {
+ boot_ok = true;
+ }
+
+ if (! _accel_logging_enabled) {
+ // logging has been disabled by user, close
+ if (_accel_log_fd != -1) {
+ ::close(_accel_log_fd);
+ _accel_log_fd = -1;
+ }
+ return;
+ }
+ if (_accel_log_fd == -1) {
+ // keep last 10 logs
+ ::unlink(ACCEL_LOGFILE ".9");
+ for (uint8_t i=8; i>0; i--) {
+ uint8_t len = strlen(ACCEL_LOGFILE)+3;
+ char log1[len], log2[len];
+ snprintf(log1, sizeof(log1), "%s.%u", ACCEL_LOGFILE, (unsigned)i);
+ snprintf(log2, sizeof(log2), "%s.%u", ACCEL_LOGFILE, (unsigned)(i+1));
+ ::rename(log1, log2);
+ }
+ ::rename(ACCEL_LOGFILE, ACCEL_LOGFILE ".1");
+
+ // open the new logfile
+ _accel_log_fd = ::open(ACCEL_LOGFILE, O_WRONLY|O_CREAT|O_TRUNC, 0666);
+ if (_accel_log_fd == -1) {
+ return;
+ }
+ }
+
+ uint64_t now = hrt_absolute_time();
+ // log accels at 1Hz
+ if (_last_log_us == 0 ||
+ now - _last_log_us > 1000*1000) {
+ _last_log_us = now;
+ ::dprintf(_accel_log_fd, "ARB %llu %.3f %.3f %.3f %d %d %d boot_ok=%u\r\n",
+ (unsigned long long)arb->timestamp,
+ (double)arb->x, (double)arb->y, (double)arb->z,
+ (int)arb->x_raw,
+ (int)arb->y_raw,
+ (int)arb->z_raw,
+ (unsigned)boot_ok);
+ }
+
+ const uint8_t reglist[] = { ADDR_WHO_AM_I, 0x02, 0x15, ADDR_STATUS_A, ADDR_STATUS_M, ADDR_CTRL_REG0, ADDR_CTRL_REG1,
+ ADDR_CTRL_REG2, ADDR_CTRL_REG3, ADDR_CTRL_REG4, ADDR_CTRL_REG5, ADDR_CTRL_REG6,
+ ADDR_CTRL_REG7, ADDR_OUT_TEMP_L, ADDR_OUT_TEMP_H, ADDR_INT_CTRL_M, ADDR_INT_SRC_M,
+ ADDR_REFERENCE_X, ADDR_REFERENCE_Y, ADDR_REFERENCE_Z, ADDR_OUT_X_L_A, ADDR_OUT_X_H_A,
+ ADDR_OUT_Y_L_A, ADDR_OUT_Y_H_A, ADDR_OUT_Z_L_A, ADDR_OUT_Z_H_A, ADDR_FIFO_CTRL,
+ ADDR_FIFO_SRC, ADDR_IG_CFG1, ADDR_IG_SRC1, ADDR_IG_THS1, ADDR_IG_DUR1, ADDR_IG_CFG2,
+ ADDR_IG_SRC2, ADDR_IG_THS2, ADDR_IG_DUR2, ADDR_CLICK_CFG, ADDR_CLICK_SRC,
+ ADDR_CLICK_THS, ADDR_TIME_LIMIT, ADDR_TIME_LATENCY, ADDR_TIME_WINDOW,
+ ADDR_ACT_THS, ADDR_ACT_DUR,
+ ADDR_OUT_X_L_M, ADDR_OUT_X_H_M,
+ ADDR_OUT_Y_L_M, ADDR_OUT_Y_H_M, ADDR_OUT_Z_L_M, ADDR_OUT_Z_H_M, 0x02, 0x15, ADDR_WHO_AM_I};
+ uint8_t regval[sizeof(reglist)];
+ for (uint8_t i=0; i<sizeof(reglist); i++) {
+ regval[i] = read_reg(reglist[i]);
+ }
+
+ // log registers at 10Hz when we have extreme values, or 0.5 Hz without
+ if (_last_log_reg_us == 0 ||
+ (is_extreme && (now - _last_log_reg_us > 250*1000)) ||
+ (now - _last_log_reg_us > 10*1000*1000)) {
+ _last_log_reg_us = now;
+ ::dprintf(_accel_log_fd, "XREG %llu", (unsigned long long)hrt_absolute_time());
+ for (uint8_t i=0; i<sizeof(reglist); i++) {
+ ::dprintf(_accel_log_fd, " %02x:%02x", (unsigned)reglist[i], (unsigned)regval[i]);
+ }
+ ::dprintf(_accel_log_fd, "\n");
+ }
+
+ // fsync at 0.1Hz
+ if (now - _last_log_sync_us > 10*1000*1000) {
+ _last_log_sync_us = now;
+ ::fsync(_accel_log_fd);
+ }
+
+ // play alarm every 10s if we have had an extreme value
+ if (perf_event_count(_extreme_values) != 0 &&
+ (now - _last_log_alarm_us > 10*1000*1000)) {
+ _last_log_alarm_us = now;
+ int tfd = ::open(TONEALARM_DEVICE_PATH, 0);
+ if (tfd != -1) {
+ uint8_t tone = 3;
+ if (!is_extreme) {
+ tone = 3;
+ } else if (boot_ok) {
+ tone = 4;
+ } else {
+ tone = 5;
+ }
+ ::ioctl(tfd, TONE_SET_ALARM, tone);
+ ::close(tfd);
+ }
+ }
+}
+
+ssize_t
+LSM303D::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct accel_report);
+ accel_report *arb = reinterpret_cast<accel_report *>(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_call_accel_interval > 0) {
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ */
+ while (count--) {
+ if (_accel_reports->get(arb)) {
+ check_extremes(arb);
+ ret += sizeof(*arb);
+ arb++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement */
+ measure();
+
+ /* measurement will have generated a report, copy it out */
+ if (_accel_reports->get(arb))
+ ret = sizeof(*arb);
+
+ return ret;
+}
+
+ssize_t
+LSM303D::mag_read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct mag_report);
+ mag_report *mrb = reinterpret_cast<mag_report *>(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_call_mag_interval > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ */
+ while (count--) {
+ if (_mag_reports->get(mrb)) {
+ ret += sizeof(*mrb);
+ mrb++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement */
+ _mag_reports->flush();
+ measure();
+
+ /* measurement will have generated a report, copy it out */
+ if (_mag_reports->get(mrb))
+ ret = sizeof(*mrb);
+
+ return ret;
+}
+
+int
+LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _call_accel_interval = 0;
+ return OK;
+
+ /* external signalling not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ return ioctl(filp, SENSORIOCSPOLLRATE, 1600);
+
+ case SENSOR_POLLRATE_DEFAULT:
+ return ioctl(filp, SENSORIOCSPOLLRATE, LSM303D_ACCEL_DEFAULT_RATE);
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_call_accel_interval == 0);
+
+ /* convert hz to hrt interval via microseconds */
+ unsigned ticks = 1000000 / arg;
+
+ /* check against maximum sane rate */
+ if (ticks < 500)
+ return -EINVAL;
+
+ /* adjust filters */
+ accel_set_driver_lowpass_filter((float)arg, _accel_filter_x.get_cutoff_freq());
+
+ /* update interval for next measurement */
+ /* XXX this is a bit shady, but no other way to adjust... */
+ _accel_call.period = _call_accel_interval = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_call_accel_interval == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return 1000000 / _call_accel_interval;
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_accel_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _accel_reports->size();
+
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
+ case ACCELIOCSSAMPLERATE:
+ return accel_set_samplerate(arg);
+
+ case ACCELIOCGSAMPLERATE:
+ return _accel_samplerate;
+
+ case ACCELIOCSLOWPASS: {
+ return accel_set_driver_lowpass_filter((float)_accel_samplerate, (float)arg);
+ }
+
+ case ACCELIOCGLOWPASS:
+ return _accel_filter_x.get_cutoff_freq();
+
+ case ACCELIOCSSCALE: {
+ /* copy scale, but only if off by a few percent */
+ struct accel_scale *s = (struct accel_scale *) arg;
+ float sum = s->x_scale + s->y_scale + s->z_scale;
+ if (sum > 2.0f && sum < 4.0f) {
+ memcpy(&_accel_scale, s, sizeof(_accel_scale));
+ return OK;
+ } else {
+ return -EINVAL;
+ }
+ }
+
+ case ACCELIOCSRANGE:
+ /* arg needs to be in G */
+ return accel_set_range(arg);
+
+ case ACCELIOCGRANGE:
+ /* convert to m/s^2 and return rounded in G */
+ return (unsigned long)((_accel_range_m_s2)/LSM303D_ONE_G + 0.5f);
+
+ case ACCELIOCGSCALE:
+ /* copy scale out */
+ memcpy((struct accel_scale *) arg, &_accel_scale, sizeof(_accel_scale));
+ return OK;
+
+ case ACCELIOCSELFTEST:
+ return accel_self_test();
+
+ default:
+ /* give it to the superclass */
+ return SPI::ioctl(filp, cmd, arg);
+ }
+}
+
+int
+LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _call_mag_interval = 0;
+ return OK;
+
+ /* external signalling 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:
+ /* 100 Hz is max for mag */
+ return mag_ioctl(filp, SENSORIOCSPOLLRATE, 100);
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_call_mag_interval == 0);
+
+ /* convert hz to hrt interval via microseconds */
+ unsigned ticks = 1000000 / arg;
+
+ /* check against maximum sane rate */
+ if (ticks < 1000)
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ /* XXX this is a bit shady, but no other way to adjust... */
+ _mag_call.period = _call_mag_interval = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_call_mag_interval == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return 1000000 / _call_mag_interval;
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_mag_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _mag_reports->size();
+
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
+ case MAGIOCSSAMPLERATE:
+ return mag_set_samplerate(arg);
+
+ case MAGIOCGSAMPLERATE:
+ return _mag_samplerate;
+
+ case MAGIOCSLOWPASS:
+ case MAGIOCGLOWPASS:
+ /* not supported, no internal filtering */
+ return -EINVAL;
+
+ case MAGIOCSSCALE:
+ /* copy scale in */
+ memcpy(&_mag_scale, (struct mag_scale *) arg, sizeof(_mag_scale));
+ return OK;
+
+ case MAGIOCGSCALE:
+ /* copy scale out */
+ memcpy((struct mag_scale *) arg, &_mag_scale, sizeof(_mag_scale));
+ return OK;
+
+ case MAGIOCSRANGE:
+ return mag_set_range(arg);
+
+ case MAGIOCGRANGE:
+ return _mag_range_ga;
+
+ case MAGIOCSELFTEST:
+ return mag_self_test();
+
+ case MAGIOCGEXTERNAL:
+ /* no external mag board yet */
+ return 0;
+
+ default:
+ /* give it to the superclass */
+ return SPI::ioctl(filp, cmd, arg);
+ }
+}
+
+int
+LSM303D::accel_self_test()
+{
+ if (_accel_read == 0)
+ return 1;
+
+ /* inspect accel offsets */
+ if (fabsf(_accel_scale.x_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.x_scale - 1.0f) > 0.4f || fabsf(_accel_scale.x_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.y_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.y_scale - 1.0f) > 0.4f || fabsf(_accel_scale.y_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.z_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.z_scale - 1.0f) > 0.4f || fabsf(_accel_scale.z_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ return 0;
+}
+
+int
+LSM303D::mag_self_test()
+{
+ if (_mag_read == 0)
+ return 1;
+
+ /**
+ * inspect mag offsets
+ * don't check mag scale because it seems this is calibrated on chip
+ */
+ if (fabsf(_mag_scale.x_offset) < 0.000001f)
+ return 1;
+
+ if (fabsf(_mag_scale.y_offset) < 0.000001f)
+ return 1;
+
+ if (fabsf(_mag_scale.z_offset) < 0.000001f)
+ return 1;
+
+ return 0;
+}
+
+uint8_t
+LSM303D::read_reg(unsigned reg)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_READ;
+ cmd[1] = 0;
+
+ transfer(cmd, cmd, sizeof(cmd));
+
+ return cmd[1];
+}
+
+void
+LSM303D::write_reg(unsigned reg, uint8_t value)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_WRITE;
+ cmd[1] = value;
+
+ transfer(cmd, nullptr, sizeof(cmd));
+}
+
+void
+LSM303D::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
+{
+ uint8_t val;
+
+ val = read_reg(reg);
+ val &= ~clearbits;
+ val |= setbits;
+ write_reg(reg, val);
+}
+
+int
+LSM303D::accel_set_range(unsigned max_g)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG2_FULL_SCALE_BITS_A;
+ float new_scale_g_digit = 0.0f;
+
+ if (max_g == 0)
+ max_g = 16;
+
+ if (max_g <= 2) {
+ _accel_range_m_s2 = 2.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_2G_A;
+ new_scale_g_digit = 0.061e-3f;
+
+ } else if (max_g <= 4) {
+ _accel_range_m_s2 = 4.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_4G_A;
+ new_scale_g_digit = 0.122e-3f;
+
+ } else if (max_g <= 6) {
+ _accel_range_m_s2 = 6.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_6G_A;
+ new_scale_g_digit = 0.183e-3f;
+
+ } else if (max_g <= 8) {
+ _accel_range_m_s2 = 8.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_8G_A;
+ new_scale_g_digit = 0.244e-3f;
+
+ } else if (max_g <= 16) {
+ _accel_range_m_s2 = 16.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_16G_A;
+ new_scale_g_digit = 0.732e-3f;
+
+ } else {
+ return -EINVAL;
+ }
+
+ _accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
+
+
+ modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::mag_set_range(unsigned max_ga)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG6_FULL_SCALE_BITS_M;
+ float new_scale_ga_digit = 0.0f;
+
+ if (max_ga == 0)
+ max_ga = 12;
+
+ if (max_ga <= 2) {
+ _mag_range_ga = 2;
+ setbits |= REG6_FULL_SCALE_2GA_M;
+ new_scale_ga_digit = 0.080e-3f;
+
+ } else if (max_ga <= 4) {
+ _mag_range_ga = 4;
+ setbits |= REG6_FULL_SCALE_4GA_M;
+ new_scale_ga_digit = 0.160e-3f;
+
+ } else if (max_ga <= 8) {
+ _mag_range_ga = 8;
+ setbits |= REG6_FULL_SCALE_8GA_M;
+ new_scale_ga_digit = 0.320e-3f;
+
+ } else if (max_ga <= 12) {
+ _mag_range_ga = 12;
+ setbits |= REG6_FULL_SCALE_12GA_M;
+ new_scale_ga_digit = 0.479e-3f;
+
+ } else {
+ return -EINVAL;
+ }
+
+ _mag_range_scale = new_scale_ga_digit;
+
+ modify_reg(ADDR_CTRL_REG6, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG2_ANTIALIAS_FILTER_BW_BITS_A;
+
+ if (bandwidth == 0)
+ bandwidth = 773;
+
+ if (bandwidth <= 50) {
+ setbits |= REG2_AA_FILTER_BW_50HZ_A;
+ _accel_onchip_filter_bandwith = 50;
+
+ } else if (bandwidth <= 194) {
+ setbits |= REG2_AA_FILTER_BW_194HZ_A;
+ _accel_onchip_filter_bandwith = 194;
+
+ } else if (bandwidth <= 362) {
+ setbits |= REG2_AA_FILTER_BW_362HZ_A;
+ _accel_onchip_filter_bandwith = 362;
+
+ } else if (bandwidth <= 773) {
+ setbits |= REG2_AA_FILTER_BW_773HZ_A;
+ _accel_onchip_filter_bandwith = 773;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_driver_lowpass_filter(float samplerate, float bandwidth)
+{
+ _accel_filter_x.set_cutoff_frequency(samplerate, bandwidth);
+ _accel_filter_y.set_cutoff_frequency(samplerate, bandwidth);
+ _accel_filter_z.set_cutoff_frequency(samplerate, bandwidth);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_samplerate(unsigned frequency)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG1_RATE_BITS_A;
+
+ if (frequency == 0)
+ frequency = 1600;
+
+ if (frequency <= 100) {
+ setbits |= REG1_RATE_100HZ_A;
+ _accel_samplerate = 100;
+
+ } else if (frequency <= 200) {
+ setbits |= REG1_RATE_200HZ_A;
+ _accel_samplerate = 200;
+
+ } else if (frequency <= 400) {
+ setbits |= REG1_RATE_400HZ_A;
+ _accel_samplerate = 400;
+
+ } else if (frequency <= 800) {
+ setbits |= REG1_RATE_800HZ_A;
+ _accel_samplerate = 800;
+
+ } else if (frequency <= 1600) {
+ setbits |= REG1_RATE_1600HZ_A;
+ _accel_samplerate = 1600;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG1, clearbits, setbits);
+ _reg1_expected = (_reg1_expected & ~clearbits) | setbits;
+
+ return OK;
+}
+
+int
+LSM303D::mag_set_samplerate(unsigned frequency)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG5_RATE_BITS_M;
+
+ if (frequency == 0)
+ frequency = 100;
+
+ if (frequency <= 25) {
+ setbits |= REG5_RATE_25HZ_M;
+ _mag_samplerate = 25;
+
+ } else if (frequency <= 50) {
+ setbits |= REG5_RATE_50HZ_M;
+ _mag_samplerate = 50;
+
+ } else if (frequency <= 100) {
+ setbits |= REG5_RATE_100HZ_M;
+ _mag_samplerate = 100;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG5, clearbits, setbits);
+
+ return OK;
+}
+
+void
+LSM303D::start()
+{
+ /* make sure we are stopped first */
+ stop();
+
+ /* reset the report ring */
+ _accel_reports->flush();
+ _mag_reports->flush();
+
+ /* start polling at the specified rate */
+ hrt_call_every(&_accel_call, 1000, _call_accel_interval, (hrt_callout)&LSM303D::measure_trampoline, this);
+ hrt_call_every(&_mag_call, 1000, _call_mag_interval, (hrt_callout)&LSM303D::mag_measure_trampoline, this);
+}
+
+void
+LSM303D::stop()
+{
+ hrt_cancel(&_accel_call);
+ hrt_cancel(&_mag_call);
+}
+
+void
+LSM303D::measure_trampoline(void *arg)
+{
+ LSM303D *dev = (LSM303D *)arg;
+
+ /* make another measurement */
+ dev->measure();
+}
+
+void
+LSM303D::mag_measure_trampoline(void *arg)
+{
+ LSM303D *dev = (LSM303D *)arg;
+
+ /* make another measurement */
+ dev->mag_measure();
+}
+
+void
+LSM303D::measure()
+{
+ // if the accel doesn't have any data ready then re-schedule
+ // for 100 microseconds later. This ensures we don't double
+ // read a value and then miss the next value
+ if (stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
+ perf_count(_accel_reschedules);
+ hrt_call_delay(&_accel_call, 100);
+ return;
+ }
+ if (read_reg(ADDR_CTRL_REG1) != _reg1_expected) {
+ perf_count(_reg1_resets);
+ reset();
+ return;
+ }
+
+ /* status register and data as read back from the device */
+
+#pragma pack(push, 1)
+ struct {
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } raw_accel_report;
+#pragma pack(pop)
+
+ accel_report accel_report;
+
+ /* start the performance counter */
+ perf_begin(_accel_sample_perf);
+
+ /* fetch data from the sensor */
+ memset(&raw_accel_report, 0, sizeof(raw_accel_report));
+ raw_accel_report.cmd = ADDR_STATUS_A | DIR_READ | ADDR_INCREMENT;
+ transfer((uint8_t *)&raw_accel_report, (uint8_t *)&raw_accel_report, sizeof(raw_accel_report));
+
+ /*
+ * 1) Scale raw value to SI units using scaling from datasheet.
+ * 2) Subtract static offset (in SI units)
+ * 3) Scale the statically calibrated values with a linear
+ * dynamically obtained factor
+ *
+ * Note: the static sensor offset is the number the sensor outputs
+ * at a nominally 'zero' input. Therefore the offset has to
+ * be subtracted.
+ *
+ * Example: A gyro outputs a value of 74 at zero angular rate
+ * the offset is 74 from the origin and subtracting
+ * 74 from all measurements centers them around zero.
+ */
+
+
+ accel_report.timestamp = hrt_absolute_time();
+ accel_report.error_count = 0; // not reported
+
+ accel_report.x_raw = raw_accel_report.x;
+ accel_report.y_raw = raw_accel_report.y;
+ accel_report.z_raw = raw_accel_report.z;
+
+ float x_in_new = ((accel_report.x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((accel_report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((accel_report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+
+ accel_report.x = _accel_filter_x.apply(x_in_new);
+ accel_report.y = _accel_filter_y.apply(y_in_new);
+ accel_report.z = _accel_filter_z.apply(z_in_new);
+
+ accel_report.scaling = _accel_range_scale;
+ accel_report.range_m_s2 = _accel_range_m_s2;
+
+ _accel_reports->force(&accel_report);
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ if (_accel_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report);
+ }
+
+ _accel_read++;
+
+ /* stop the perf counter */
+ perf_end(_accel_sample_perf);
+}
+
+void
+LSM303D::mag_measure()
+{
+ if (read_reg(ADDR_CTRL_REG7) != _reg7_expected) {
+ perf_count(_reg7_resets);
+ reset();
+ return;
+ }
+
+ /* status register and data as read back from the device */
+#pragma pack(push, 1)
+ struct {
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } raw_mag_report;
+#pragma pack(pop)
+
+ mag_report mag_report;
+
+ /* start the performance counter */
+ perf_begin(_mag_sample_perf);
+
+ /* fetch data from the sensor */
+ memset(&raw_mag_report, 0, sizeof(raw_mag_report));
+ raw_mag_report.cmd = ADDR_STATUS_M | DIR_READ | ADDR_INCREMENT;
+ transfer((uint8_t *)&raw_mag_report, (uint8_t *)&raw_mag_report, sizeof(raw_mag_report));
+
+ /*
+ * 1) Scale raw value to SI units using scaling from datasheet.
+ * 2) Subtract static offset (in SI units)
+ * 3) Scale the statically calibrated values with a linear
+ * dynamically obtained factor
+ *
+ * Note: the static sensor offset is the number the sensor outputs
+ * at a nominally 'zero' input. Therefore the offset has to
+ * be subtracted.
+ *
+ * Example: A gyro outputs a value of 74 at zero angular rate
+ * the offset is 74 from the origin and subtracting
+ * 74 from all measurements centers them around zero.
+ */
+
+
+ mag_report.timestamp = hrt_absolute_time();
+
+ mag_report.x_raw = raw_mag_report.x;
+ mag_report.y_raw = raw_mag_report.y;
+ mag_report.z_raw = raw_mag_report.z;
+ mag_report.x = ((mag_report.x_raw * _mag_range_scale) - _mag_scale.x_offset) * _mag_scale.x_scale;
+ mag_report.y = ((mag_report.y_raw * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
+ mag_report.z = ((mag_report.z_raw * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
+ mag_report.scaling = _mag_range_scale;
+ mag_report.range_ga = (float)_mag_range_ga;
+
+ _mag_reports->force(&mag_report);
+
+ /* XXX please check this poll_notify, is it the right one? */
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ if (_mag->_mag_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report);
+ }
+
+ _mag_read++;
+
+ /* stop the perf counter */
+ perf_end(_mag_sample_perf);
+}
+
+void
+LSM303D::print_info()
+{
+ printf("accel reads: %u\n", _accel_read);
+ printf("mag reads: %u\n", _mag_read);
+ perf_print_counter(_accel_sample_perf);
+ _accel_reports->print_info("accel reports");
+ _mag_reports->print_info("mag reports");
+}
+
+void
+LSM303D::print_registers()
+{
+ const struct {
+ uint8_t reg;
+ const char *name;
+ } regmap[] = {
+ { ADDR_WHO_AM_I, "WHO_AM_I" },
+ { 0x02, "I2C_CONTROL1" },
+ { 0x15, "I2C_CONTROL2" },
+ { ADDR_STATUS_A, "STATUS_A" },
+ { ADDR_STATUS_M, "STATUS_M" },
+ { ADDR_CTRL_REG0, "CTRL_REG0" },
+ { ADDR_CTRL_REG1, "CTRL_REG1" },
+ { ADDR_CTRL_REG2, "CTRL_REG2" },
+ { ADDR_CTRL_REG3, "CTRL_REG3" },
+ { ADDR_CTRL_REG4, "CTRL_REG4" },
+ { ADDR_CTRL_REG5, "CTRL_REG5" },
+ { ADDR_CTRL_REG6, "CTRL_REG6" },
+ { ADDR_CTRL_REG7, "CTRL_REG7" },
+ { ADDR_OUT_TEMP_L, "TEMP_L" },
+ { ADDR_OUT_TEMP_H, "TEMP_H" },
+ { ADDR_INT_CTRL_M, "INT_CTRL_M" },
+ { ADDR_INT_SRC_M, "INT_SRC_M" },
+ { ADDR_REFERENCE_X, "REFERENCE_X" },
+ { ADDR_REFERENCE_Y, "REFERENCE_Y" },
+ { ADDR_REFERENCE_Z, "REFERENCE_Z" },
+ { ADDR_OUT_X_L_A, "ACCEL_XL" },
+ { ADDR_OUT_X_H_A, "ACCEL_XH" },
+ { ADDR_OUT_Y_L_A, "ACCEL_YL" },
+ { ADDR_OUT_Y_H_A, "ACCEL_YH" },
+ { ADDR_OUT_Z_L_A, "ACCEL_ZL" },
+ { ADDR_OUT_Z_H_A, "ACCEL_ZH" },
+ { ADDR_FIFO_CTRL, "FIFO_CTRL" },
+ { ADDR_FIFO_SRC, "FIFO_SRC" },
+ { ADDR_IG_CFG1, "IG_CFG1" },
+ { ADDR_IG_SRC1, "IG_SRC1" },
+ { ADDR_IG_THS1, "IG_THS1" },
+ { ADDR_IG_DUR1, "IG_DUR1" },
+ { ADDR_IG_CFG2, "IG_CFG2" },
+ { ADDR_IG_SRC2, "IG_SRC2" },
+ { ADDR_IG_THS2, "IG_THS2" },
+ { ADDR_IG_DUR2, "IG_DUR2" },
+ { ADDR_CLICK_CFG, "CLICK_CFG" },
+ { ADDR_CLICK_SRC, "CLICK_SRC" },
+ { ADDR_CLICK_THS, "CLICK_THS" },
+ { ADDR_TIME_LIMIT, "TIME_LIMIT" },
+ { ADDR_TIME_LATENCY,"TIME_LATENCY" },
+ { ADDR_TIME_WINDOW, "TIME_WINDOW" },
+ { ADDR_ACT_THS, "ACT_THS" },
+ { ADDR_ACT_DUR, "ACT_DUR" }
+ };
+ for (uint8_t i=0; i<sizeof(regmap)/sizeof(regmap[0]); i++) {
+ printf("0x%02x %s\n", read_reg(regmap[i].reg), regmap[i].name);
+ }
+ printf("_reg1_expected=0x%02x\n", _reg1_expected);
+ printf("_reg7_expected=0x%02x\n", _reg7_expected);
+}
+
+void
+LSM303D::toggle_logging()
+{
+ if (! _accel_logging_enabled) {
+ _accel_logging_enabled = true;
+ printf("Started logging to %s\n", ACCEL_LOGFILE);
+ } else {
+ _accel_logging_enabled = false;
+ printf("Stopped logging\n");
+ }
+}
+
+LSM303D_mag::LSM303D_mag(LSM303D *parent) :
+ CDev("LSM303D_mag", LSM303D_DEVICE_PATH_MAG),
+ _parent(parent),
+ _mag_topic(-1),
+ _mag_class_instance(-1)
+{
+}
+
+LSM303D_mag::~LSM303D_mag()
+{
+ if (_mag_class_instance != -1)
+ unregister_class_devname(MAG_DEVICE_PATH, _mag_class_instance);
+}
+
+int
+LSM303D_mag::init()
+{
+ int ret;
+
+ ret = CDev::init();
+ if (ret != OK)
+ goto out;
+
+ _mag_class_instance = register_class_devname(MAG_DEVICE_PATH);
+
+out:
+ return ret;
+}
+
+void
+LSM303D_mag::parent_poll_notify()
+{
+ poll_notify(POLLIN);
+}
+
+ssize_t
+LSM303D_mag::read(struct file *filp, char *buffer, size_t buflen)
+{
+ return _parent->mag_read(filp, buffer, buflen);
+}
+
+int
+LSM303D_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ return _parent->mag_ioctl(filp, cmd, arg);
+}
+
+void
+LSM303D_mag::measure()
+{
+ _parent->mag_measure();
+}
+
+void
+LSM303D_mag::measure_trampoline(void *arg)
+{
+ _parent->mag_measure_trampoline(arg);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace lsm303d
+{
+
+LSM303D *g_dev;
+
+void start();
+void test();
+void reset();
+void info();
+void regdump();
+void logging();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ int fd, fd_mag;
+
+ if (g_dev != nullptr)
+ errx(0, "already started");
+
+ /* create the driver */
+ g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+
+ if (g_dev == nullptr) {
+ warnx("failed instantiating LSM303D obj");
+ goto fail;
+ }
+
+ if (OK != g_dev->init())
+ goto fail;
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(LSM303D_DEVICE_PATH_ACCEL, O_RDONLY);
+
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+
+ fd_mag = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
+
+ /* don't fail if open cannot be opened */
+ if (0 <= fd_mag) {
+ if (ioctl(fd_mag, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ goto fail;
+ }
+ }
+
+ close(fd);
+ close(fd_mag);
+
+ exit(0);
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ int fd_accel = -1;
+ struct accel_report accel_report;
+ ssize_t sz;
+ int ret;
+
+ /* get the driver */
+ fd_accel = open(LSM303D_DEVICE_PATH_ACCEL, O_RDONLY);
+
+ if (fd_accel < 0)
+ err(1, "%s open failed", LSM303D_DEVICE_PATH_ACCEL);
+
+ /* do a simple demand read */
+ sz = read(fd_accel, &accel_report, sizeof(accel_report));
+
+ if (sz != sizeof(accel_report))
+ err(1, "immediate read failed");
+
+
+ warnx("accel x: \t% 9.5f\tm/s^2", (double)accel_report.x);
+ warnx("accel y: \t% 9.5f\tm/s^2", (double)accel_report.y);
+ warnx("accel z: \t% 9.5f\tm/s^2", (double)accel_report.z);
+ warnx("accel x: \t%d\traw", (int)accel_report.x_raw);
+ warnx("accel y: \t%d\traw", (int)accel_report.y_raw);
+ warnx("accel z: \t%d\traw", (int)accel_report.z_raw);
+
+ warnx("accel range: %8.4f m/s^2", (double)accel_report.range_m_s2);
+ if (ERROR == (ret = ioctl(fd_accel, ACCELIOCGLOWPASS, 0)))
+ warnx("accel antialias filter bandwidth: fail");
+ else
+ warnx("accel antialias filter bandwidth: %d Hz", ret);
+
+ int fd_mag = -1;
+ struct mag_report m_report;
+
+ /* get the driver */
+ fd_mag = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
+
+ if (fd_mag < 0)
+ err(1, "%s open failed", LSM303D_DEVICE_PATH_MAG);
+
+ /* check if mag is onboard or external */
+ if ((ret = ioctl(fd_mag, MAGIOCGEXTERNAL, 0)) < 0)
+ errx(1, "failed to get if mag is onboard or external");
+ warnx("mag device active: %s", ret ? "external" : "onboard");
+
+ /* do a simple demand read */
+ sz = read(fd_mag, &m_report, sizeof(m_report));
+
+ if (sz != sizeof(m_report))
+ err(1, "immediate read failed");
+
+ warnx("mag x: \t% 9.5f\tga", (double)m_report.x);
+ warnx("mag y: \t% 9.5f\tga", (double)m_report.y);
+ warnx("mag z: \t% 9.5f\tga", (double)m_report.z);
+ warnx("mag x: \t%d\traw", (int)m_report.x_raw);
+ warnx("mag y: \t%d\traw", (int)m_report.y_raw);
+ warnx("mag z: \t%d\traw", (int)m_report.z_raw);
+ warnx("mag range: %8.4f ga", (double)m_report.range_ga);
+
+ /* XXX add poll-rate tests here too */
+
+ close(fd_accel);
+ close(fd_mag);
+
+ reset();
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(LSM303D_DEVICE_PATH_ACCEL, 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, "accel pollrate reset failed");
+
+ close(fd);
+
+ fd = open(LSM303D_DEVICE_PATH_MAG, O_RDONLY);
+
+ if (fd < 0) {
+ warnx("mag could not be opened, external mag might be used");
+ } else {
+ /* no need to reset the mag as well, the reset() is the same */
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ err(1, "mag pollrate reset failed");
+ }
+
+ close(fd);
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running\n");
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+/**
+ * dump registers from device
+ */
+void
+regdump()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running\n");
+
+ printf("regdump @ %p\n", g_dev);
+ g_dev->print_registers();
+
+ exit(0);
+}
+
+/**
+ * toggle logging
+ */
+void
+logging()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running\n");
+
+ g_dev->toggle_logging();
+
+ exit(0);
+}
+
+
+} // namespace
+
+int
+lsm303d_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+
+ */
+ if (!strcmp(argv[1], "start"))
+ lsm303d::start();
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ lsm303d::test();
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset"))
+ lsm303d::reset();
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info"))
+ lsm303d::info();
+
+ /*
+ * dump device registers
+ */
+ if (!strcmp(argv[1], "regdump"))
+ lsm303d::regdump();
+
+ /*
+ * dump device registers
+ */
+ if (!strcmp(argv[1], "logging"))
+ lsm303d::logging();
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'logging' or 'regdump'");
+}
diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk
new file mode 100644
index 000000000..e40f718c5
--- /dev/null
+++ b/src/drivers/lsm303d/module.mk
@@ -0,0 +1,8 @@
+#
+# LSM303D accel/mag driver
+#
+
+MODULE_COMMAND = lsm303d
+SRCS = lsm303d.cpp
+
+
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index 397686e8b..c910e2890 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -59,17 +59,18 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.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 MB12XX_BUS PX4_I2C_BUS_EXPANSION
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
@@ -119,10 +120,7 @@ private:
float _min_distance;
float _max_distance;
work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- range_finder_report *_reports;
+ RingBuffer *_reports;
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
@@ -183,9 +181,6 @@ private:
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
/*
* Driver 'main' command.
*/
@@ -195,9 +190,6 @@ MB12XX::MB12XX(int bus, int address) :
I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000),
_min_distance(MB12XX_MIN_DISTANCE),
_max_distance(MB12XX_MAX_DISTANCE),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
@@ -221,7 +213,7 @@ MB12XX::~MB12XX()
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
}
int
@@ -234,17 +226,15 @@ MB12XX::init()
goto out;
/* allocate basic report buffers */
- _num_reports = 2;
- _reports = new struct range_finder_report[_num_reports];
+ _reports = new RingBuffer(2, sizeof(range_finder_report));
if (_reports == nullptr)
goto out;
- _oldest_report = _next_report = 0;
-
/* get a publish handle on the range finder topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &_reports[0]);
+ struct range_finder_report zero_report;
+ memset(&zero_report, 0, sizeof(zero_report));
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report);
if (_range_finder_topic < 0)
debug("failed to create sensor_range_finder object. Did you start uOrb?");
@@ -354,31 +344,22 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
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 range_finder_report *buf = new struct range_finder_report[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;
+ /* 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 _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
/* XXX implement this */
@@ -406,6 +387,7 @@ ssize_t
MB12XX::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 */
@@ -421,10 +403,9 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen)
* 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 (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
}
}
@@ -433,9 +414,8 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement - run one conversion */
- /* XXX really it'd be nice to lock against other readers here */
do {
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* trigger a measurement */
if (OK != measure()) {
@@ -453,8 +433,9 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen)
}
/* state machine will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
} while (0);
@@ -498,26 +479,26 @@ MB12XX::collect()
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 * 1.0f)/ 100.0f; /* cm 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 */
- _reports[_next_report].timestamp = hrt_absolute_time();
- _reports[_next_report].distance = si_units;
- _reports[_next_report].valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.distance = si_units;
+ report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
/* publish it */
- orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &_reports[_next_report]);
-
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
- /* if we are running up against the oldest report, toss it */
- if (_next_report == _oldest_report) {
+ if (_reports->force(&report)) {
perf_count(_buffer_overflows);
- INCREMENT(_oldest_report, _num_reports);
}
/* notify anyone waiting for data */
@@ -525,11 +506,8 @@ MB12XX::collect()
ret = OK;
-out:
perf_end(_sample_perf);
return ret;
-
- return ret;
}
void
@@ -537,7 +515,7 @@ MB12XX::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 1);
@@ -626,8 +604,7 @@ MB12XX::print_info()
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);
+ _reports->print_info("report queue");
}
/**
diff --git a/src/drivers/md25/BlockSysIdent.cpp b/src/drivers/md25/BlockSysIdent.cpp
new file mode 100644
index 000000000..23b0724d8
--- /dev/null
+++ b/src/drivers/md25/BlockSysIdent.cpp
@@ -0,0 +1,8 @@
+#include "BlockSysIdent.hpp"
+
+BlockSysIdent::BlockSysIdent() :
+ Block(NULL, "SYSID"),
+ _freq(this, "FREQ"),
+ _ampl(this, "AMPL")
+{
+}
diff --git a/src/drivers/md25/BlockSysIdent.hpp b/src/drivers/md25/BlockSysIdent.hpp
new file mode 100644
index 000000000..270635f40
--- /dev/null
+++ b/src/drivers/md25/BlockSysIdent.hpp
@@ -0,0 +1,10 @@
+#include <controllib/block/Block.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+class BlockSysIdent : public control::Block {
+public:
+ BlockSysIdent();
+private:
+ control::BlockParam<float> _freq;
+ control::BlockParam<float> _ampl;
+};
diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp
index 71932ad65..d43e3aef9 100644
--- a/src/drivers/md25/md25.cpp
+++ b/src/drivers/md25/md25.cpp
@@ -45,9 +45,16 @@
#include "md25.hpp"
#include <poll.h>
#include <stdio.h>
+#include <math.h>
+#include <string.h>
#include <systemlib/err.h>
#include <arch/board/board.h>
+#include <mavlink/mavlink_log.h>
+
+#include <controllib/uorb/UOrbPublication.hpp>
+#include <uORB/topics/debug_key_value.h>
+#include <drivers/drv_hrt.h>
// registers
enum {
@@ -72,6 +79,9 @@ enum {
REG_COMMAND_RW,
};
+// File descriptors
+static int mavlink_fd;
+
MD25::MD25(const char *deviceName, int bus,
uint16_t address, uint32_t speed) :
I2C("MD25", deviceName, bus, address, speed),
@@ -106,7 +116,8 @@ MD25::MD25(const char *deviceName, int bus,
setMotor2Speed(0);
resetEncoders();
_setMode(MD25::MODE_UNSIGNED_SPEED);
- setSpeedRegulation(true);
+ setSpeedRegulation(false);
+ setMotorAccel(10);
setTimeout(true);
}
@@ -298,6 +309,12 @@ int MD25::setDeviceAddress(uint8_t address)
return OK;
}
+int MD25::setMotorAccel(uint8_t accel)
+{
+ return _writeUint8(REG_ACCEL_RATE_RW,
+ accel);
+}
+
int MD25::setMotor1Speed(float value)
{
return _writeUint8(REG_SPEED1_RW,
@@ -451,12 +468,12 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
MD25 md25("/dev/md25", bus, address);
// print status
- char buf[200];
+ char buf[400];
md25.status(buf, sizeof(buf));
printf("%s\n", buf);
// setup for test
- md25.setSpeedRegulation(true);
+ md25.setSpeedRegulation(false);
md25.setTimeout(true);
float dt = 0.1;
float speed = 0.2;
@@ -550,4 +567,68 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
return 0;
}
+int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency)
+{
+ printf("md25 sine: starting\n");
+
+ // setup
+ MD25 md25("/dev/md25", bus, address);
+
+ // print status
+ char buf[400];
+ md25.status(buf, sizeof(buf));
+ printf("%s\n", buf);
+
+ // setup for test
+ md25.setSpeedRegulation(false);
+ md25.setTimeout(true);
+ float dt = 0.01;
+ float t_final = 60.0;
+ float prev_revolution = md25.getRevolutions1();
+
+ // debug publication
+ control::UOrbPublication<debug_key_value_s> debug_msg(NULL,
+ ORB_ID(debug_key_value));
+
+ // sine wave for motor 1
+ md25.resetEncoders();
+ while (true) {
+
+ // input
+ uint64_t timestamp = hrt_absolute_time();
+ float t = timestamp/1000000.0f;
+
+ float input_value = amplitude*sinf(2*M_PI*frequency*t);
+ md25.setMotor1Speed(input_value);
+
+ // output
+ md25.readData();
+ float current_revolution = md25.getRevolutions1();
+
+ // send input message
+ //strncpy(debug_msg.key, "md25 in ", 10);
+ //debug_msg.timestamp_ms = 1000*timestamp;
+ //debug_msg.value = input_value;
+ //debug_msg.update();
+
+ // send output message
+ strncpy(debug_msg.key, "md25 out ", 10);
+ debug_msg.timestamp_ms = 1000*timestamp;
+ debug_msg.value = current_revolution;
+ debug_msg.update();
+
+ if (t > t_final) break;
+
+ // update for next step
+ prev_revolution = current_revolution;
+
+ // sleep
+ usleep(1000000 * dt);
+ }
+ md25.setMotor1Speed(0);
+
+ printf("md25 sine complete\n");
+ return 0;
+}
+
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp
index e77511b16..1661f67f9 100644
--- a/src/drivers/md25/md25.hpp
+++ b/src/drivers/md25/md25.hpp
@@ -46,7 +46,7 @@
#include <poll.h>
#include <stdio.h>
-#include <controllib/block/UOrbSubscription.hpp>
+#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>
@@ -213,6 +213,19 @@ public:
int setDeviceAddress(uint8_t address);
/**
+ * set motor acceleration
+ * @param accel
+ * controls motor speed change (1-10)
+ * accel rate | time for full fwd. to full rev.
+ * 1 | 6.375 s
+ * 2 | 1.6 s
+ * 3 | 0.675 s
+ * 5(default) | 1.275 s
+ * 10 | 0.65 s
+ */
+ int setMotorAccel(uint8_t accel);
+
+ /**
* set motor 1 speed
* @param normSpeed normalize speed between -1 and 1
* @return non-zero -> error
@@ -290,4 +303,7 @@ private:
// unit testing
int md25Test(const char *deviceName, uint8_t bus, uint8_t address);
+// sine testing
+int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency);
+
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp
index e62c46b0d..7e5904d05 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -82,7 +82,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n");
+ fprintf(stderr, "usage: md25 {start|stop|read|status|search|test|change_address}\n\n");
exit(1);
}
@@ -136,6 +136,28 @@ int md25_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "sine")) {
+
+ if (argc < 6) {
+ printf("usage: md25 sine bus address amp freq\n");
+ exit(0);
+ }
+
+ const char *deviceName = "/dev/md25";
+
+ uint8_t bus = strtoul(argv[2], nullptr, 0);
+
+ uint8_t address = strtoul(argv[3], nullptr, 0);
+
+ float amplitude = atof(argv[4]);
+
+ float frequency = atof(argv[5]);
+
+ md25Sine(deviceName, bus, address, amplitude, frequency);
+
+ exit(0);
+ }
+
if (!strcmp(argv[1], "probe")) {
if (argc < 4) {
printf("usage: md25 probe bus address\n");
@@ -162,6 +184,29 @@ int md25_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "read")) {
+ if (argc < 4) {
+ printf("usage: md25 read bus address\n");
+ exit(0);
+ }
+
+ const char *deviceName = "/dev/md25";
+
+ uint8_t bus = strtoul(argv[2], nullptr, 0);
+
+ uint8_t address = strtoul(argv[3], nullptr, 0);
+
+ MD25 md25(deviceName, bus, address);
+
+ // print status
+ char buf[400];
+ md25.status(buf, sizeof(buf));
+ printf("%s\n", buf);
+
+ exit(0);
+ }
+
+
if (!strcmp(argv[1], "search")) {
if (argc < 3) {
printf("usage: md25 search bus\n");
@@ -246,7 +291,7 @@ int md25_thread_main(int argc, char *argv[])
uint8_t address = strtoul(argv[4], nullptr, 0);
// start
- MD25 md25("/dev/md25", bus, address);
+ MD25 md25(deviceName, bus, address);
thread_running = true;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
new file mode 100644
index 000000000..05ae21c1f
--- /dev/null
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -0,0 +1,520 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 Sarthak Kaingade
+ * @author Simon Wilks
+ * @author Thomas Gubler
+ *
+ * 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/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
+ */
+
+#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 <board_config.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <drivers/airspeed/airspeed.h>
+
+/* I2C bus address is 1010001x */
+#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 //0x77/* 7-bit address, addr. pin pulled low */
+
+/* Register address */
+#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
+
+/* Measurement rate is 100Hz */
+#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
+
+class MEASAirspeed : public Airspeed
+{
+public:
+ MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO);
+
+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 = 0;
+ ret = transfer(&cmd, 1, nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ }
+
+ return ret;
+}
+
+int
+MEASAirspeed::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[4] = {0, 0, 0, 0};
+
+
+ perf_begin(_sample_perf);
+
+ ret = transfer(nullptr, 0, &val[0], 4);
+
+ if (ret < 0) {
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+ uint8_t status = val[0] & 0xC0;
+
+ if (status == 2) {
+ log("err: stale data");
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ } else if (status == 3) {
+ log("err: fault");
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+ int16_t dp_raw = 0, dT_raw = 0;
+ dp_raw = (val[0] << 8) + val[1];
+ /* mask the used bits */
+ dp_raw = 0x3FFF & dp_raw;
+ dT_raw = (val[2] << 8) + val[3];
+ dT_raw = (0xFFE0 & dT_raw) >> 5;
+ float temperature = ((200 * dT_raw) / 2047) - 50;
+
+ /* calculate differential pressure. As its centered around 8000
+ * and can go positive or negative, enforce absolute value
+ */
+ const float P_min = -1.0f;
+ const float P_max = 1.0f;
+ float diff_press_pa = fabsf( ( ((float)dp_raw - 0.1f*16383.0f) * (P_max-P_min)/(0.8f*16383.0f) + P_min) * 6894.8f) - _diff_pres_offset;
+ if (diff_press_pa < 0.0f)
+ diff_press_pa = 0.0f;
+
+ struct differential_pressure_s report;
+
+ /* track maximum differential pressure measured (so we can work out top speed). */
+ if (diff_press_pa > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_press_pa;
+ }
+
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.temperature = temperature;
+ report.differential_pressure_pa = diff_press_pa;
+ report.voltage = 0;
+ report.max_differential_pressure_pa = _max_differential_pressure_pa;
+
+ if (_airspeed_pub > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
+ }
+
+ new_report(report);
+
+ /* 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()) {
+ /* 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 = nullptr;
+
+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, 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->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;
+
+ /* 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);
+
+ 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", (double)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);
+ warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
+ }
+
+ /* reset the sensor polling to its default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
+ errx(1, "failed to set default rate");
+
+ 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..fed4078b6
--- /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 = 2048
+
+SRCS = meas_airspeed.cpp
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index b54b7aba1..705e98eea 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -1,6 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
+ * Author: Marco Bauer <marco@wtns.de>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +36,8 @@
* @file mkblctrl.cpp
*
* Driver/configurator for the Mikrokopter BL-Ctrl.
- * Marco Bauer
+ *
+ * @author Marco Bauer <marco@wtns.de>
*
*/
@@ -59,10 +61,10 @@
#include <nuttx/arch.h>
#include <nuttx/i2c.h>
+#include <board_config.h>
+
#include <drivers/device/device.h>
#include <drivers/drv_pwm_output.h>
-#include <drivers/drv_gpio.h>
-#include <drivers/boards/px4fmu/px4fmu_internal.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_rc_input.h>
@@ -72,8 +74,9 @@
#include <drivers/drv_mixer.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/esc_status.h>
#include <systemlib/err.h>
@@ -86,18 +89,15 @@
#define BLCTRL_MIN_VALUE -0.920F
#define MOTOR_STATE_PRESENT_MASK 0x80
#define MOTOR_STATE_ERROR_MASK 0x7F
-#define MOTOR_SPINUP_COUNTER 2500
+#define MOTOR_SPINUP_COUNTER 30
+#define ESC_UORB_PUBLISH_DELAY 500000
+
+
class MK : public device::I2C
{
public:
- enum Mode {
- MODE_2PWM,
- MODE_4PWM,
- MODE_NONE
- };
-
enum MappingMode {
MAPPING_MK = 0,
MAPPING_PX4,
@@ -108,39 +108,42 @@ public:
FRAME_X,
};
- MK(int bus);
+ MK(int bus, const char *_device_path);
~MK();
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual int init(unsigned motors);
virtual ssize_t write(file *filp, const char *buffer, size_t len);
- int set_mode(Mode mode);
- int set_pwm_rate(unsigned rate);
+ int set_update_rate(unsigned rate);
int set_motor_count(unsigned count);
int set_motor_test(bool motortest);
+ int set_overrideSecurityChecks(bool overrideSecurityChecks);
int set_px4mode(int px4mode);
int set_frametype(int frametype);
- unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput);
+ unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C);
private:
static const unsigned _max_actuators = MAX_MOTORS;
static const bool showDebug = false;
- Mode _mode;
int _update_rate;
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_armed;
unsigned int _motor;
int _px4mode;
int _frametype;
+ char _device[20]; ///< device
+
orb_advert_t _t_outputs;
- orb_advert_t _t_actuators_effective;
+ orb_advert_t _t_esc_status;
+
unsigned int _num_outputs;
bool _primary_pwm_device;
bool _motortest;
+ bool _overrideSecurityChecks;
volatile bool _task_should_exit;
bool _armed;
@@ -170,33 +173,15 @@ private:
static const GPIOConfig _gpio_tab[];
static const unsigned _ngpio;
- void gpio_reset(void);
- void gpio_set_function(uint32_t gpios, int function);
- void gpio_write(uint32_t gpios, int function);
- uint32_t gpio_read(void);
- int gpio_ioctl(file *filp, int cmd, unsigned long arg);
int mk_servo_arm(bool status);
-
int mk_servo_set(unsigned int chan, short val);
int mk_servo_set_value(unsigned int chan, short val);
int mk_servo_test(unsigned int chan);
short scaling(float val, float inMin, float inMax, float outMin, float outMax);
-
-
};
-const MK::GPIOConfig MK::_gpio_tab[] = {
- {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
- {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
- {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
- {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1},
- {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1},
- {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
- {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
- {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
-};
-const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]);
+
const int blctrlAddr_quad_plus[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad + configuration
const int blctrlAddr_hexa_plus[] = { 0, 2, 2, -2, 1, -3, 0, 0 }; // Addresstranslator for Hexa + configuration
@@ -214,6 +199,7 @@ struct MotorData_t {
unsigned int Version; // the version of the BL (0 = old)
unsigned int SetPoint; // written by attitude controller
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
unsigned int ReadMode; // select data to read
unsigned short RawPwmValue; // length of PWM pulse
@@ -234,17 +220,17 @@ MK *g_mk;
} // namespace
-MK::MK(int bus) :
+MK::MK(int bus, const char *_device_path) :
I2C("mkblctrl", "/dev/mkblctrl", bus, 0, I2C_BUS_SPEED),
- _mode(MODE_NONE),
- _update_rate(50),
+ _update_rate(400),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_armed(-1),
_t_outputs(0),
- _t_actuators_effective(0),
+ _t_esc_status(0),
_num_outputs(0),
_motortest(false),
+ _overrideSecurityChecks(false),
_motor(-1),
_px4mode(MAPPING_MK),
_frametype(FRAME_PLUS),
@@ -253,6 +239,10 @@ MK::MK(int bus) :
_armed(false),
_mixers(nullptr)
{
+ strncpy(_device, _device_path, sizeof(_device));
+ /* enforce null termination */
+ _device[sizeof(_device) - 1] = '\0';
+
_debug_enabled = true;
}
@@ -279,7 +269,7 @@ MK::~MK()
/* clean up the alternate device node */
if (_primary_pwm_device)
- unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+ unregister_driver(_device);
g_mk = nullptr;
}
@@ -301,24 +291,23 @@ MK::init(unsigned motors)
usleep(500000);
- /* 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);
+ if (sizeof(_device) > 0) {
+ ret = register_driver(_device, &fops, 0666, (void *)this);
- if (ret == OK) {
- log("default PWM output device");
- _primary_pwm_device = true;
- }
+ if (ret == OK) {
+ log("creating alternate output device");
+ _primary_pwm_device = true;
+ }
- /* reset GPIOs */
- gpio_reset();
+ }
/* start the IO interface task */
_task = task_spawn_cmd("mkblctrl",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 20,
- 2048,
- (main_t)&MK::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 20,
+ 2048,
+ (main_t)&MK::task_main_trampoline,
+ nullptr);
if (_task < 0) {
@@ -336,43 +325,7 @@ MK::task_main_trampoline(int argc, char *argv[])
}
int
-MK::set_mode(Mode mode)
-{
- /*
- * Configure for PWM output.
- *
- * Note that regardless of the configured mode, the task is always
- * listening and mixing; the mode just selects which of the channels
- * are presented on the output pins.
- */
- switch (mode) {
- case MODE_2PWM:
- up_pwm_servo_deinit();
- _update_rate = UPDATE_RATE; /* default output rate */
- break;
-
- case MODE_4PWM:
- up_pwm_servo_deinit();
- _update_rate = UPDATE_RATE; /* default output rate */
- break;
-
- case MODE_NONE:
- debug("MODE_NONE");
- /* disable servo outputs and set a very low update rate */
- up_pwm_servo_deinit();
- _update_rate = UPDATE_RATE;
- break;
-
- default:
- return -EINVAL;
- }
-
- _mode = mode;
- return OK;
-}
-
-int
-MK::set_pwm_rate(unsigned rate)
+MK::set_update_rate(unsigned rate)
{
if ((rate > 500) || (rate < 10))
return -EINVAL;
@@ -464,6 +417,13 @@ MK::set_motor_test(bool motortest)
return OK;
}
+int
+MK::set_overrideSecurityChecks(bool overrideSecurityChecks)
+{
+ _overrideSecurityChecks = overrideSecurityChecks;
+ return OK;
+}
+
short
MK::scaling(float val, float inMin, float inMax, float outMin, float outMax)
{
@@ -496,8 +456,8 @@ MK::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -506,20 +466,17 @@ MK::task_main()
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
&outputs);
+ /* advertise the blctrl status */
+ esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+ _t_esc_status = orb_advertise(ORB_ID(esc_status), &esc);
- /* advertise the effective control inputs */
- actuator_controls_effective_s controls_effective;
- memset(&controls_effective, 0, sizeof(controls_effective));
- /* advertise the effective control inputs */
- _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1),
- &controls_effective);
-
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_armed;
fds[1].events = POLLIN;
log("starting");
@@ -572,9 +529,6 @@ MK::task_main()
outputs.noutputs = _mixers->mix(&outputs.output[0], _num_outputs);
outputs.timestamp = hrt_absolute_time();
- // XXX output actual limited values
- memcpy(&controls_effective, &_controls, sizeof(controls_effective));
-
/* iterate actuators */
for (unsigned int i = 0; i < _num_outputs; i++) {
@@ -602,17 +556,21 @@ MK::task_main()
}
}
- /* don't go under BLCTRL_MIN_VALUE */
- if (outputs.output[i] < BLCTRL_MIN_VALUE) {
- outputs.output[i] = BLCTRL_MIN_VALUE;
+ if (!_overrideSecurityChecks) {
+ /* don't go under BLCTRL_MIN_VALUE */
+
+ if (outputs.output[i] < BLCTRL_MIN_VALUE) {
+ outputs.output[i] = BLCTRL_MIN_VALUE;
+ }
+
}
/* output to BLCtrl's */
- if (_motortest == true) {
- mk_servo_test(i);
-
- } else {
- mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ if (_motortest != true) {
+ //mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ // 11 Bit
+ Motor[i].SetPoint_PX4 = outputs.output[i];
+ mk_servo_set(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 2047)); // scale the output to 0 - 2047 and sent to output routine
}
}
@@ -628,18 +586,62 @@ MK::task_main()
actuator_armed_s aa;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
/* update PWM servo armed status if armed and not locked down */
mk_servo_arm(aa.armed && !aa.lockdown);
}
+
+ /*
+ * Only update esc topic every half second.
+ */
+
+ if (hrt_absolute_time() - esc.timestamp > ESC_UORB_PUBLISH_DELAY) {
+ esc.counter++;
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = (uint8_t) _num_outputs;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_I2C;
+
+ for (unsigned int i = 0; i < _num_outputs; i++) {
+ esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
+ esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
+ esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
+ esc.esc[i].esc_voltage = (uint16_t) 0;
+ esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
+ esc.esc[i].esc_rpm = (uint16_t) 0;
+ esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
+
+ if (Motor[i].Version == 1) {
+ // BLCtrl 2.0 (11Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t)(Motor[i].SetPoint << 3) | Motor[i].SetPointLowerBits;
+
+ } else {
+ // BLCtrl < 2.0 (8Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
+ }
+
+ esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
+ esc.esc[i].esc_state = (uint16_t) Motor[i].State;
+ esc.esc[i].esc_errorcount = (uint16_t) 0;
+
+ // if motortest is requested - do it...
+ if (_motortest == true) {
+ mk_servo_test(i);
+ }
+
+ }
+
+ orb_publish(ORB_ID(esc_status), _t_esc_status, &esc);
+
+ }
+
}
+ ::close(_t_esc_status);
::close(_t_actuators);
- ::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_armed);
/* make sure servos are off */
@@ -664,8 +666,12 @@ MK::mk_servo_arm(bool status)
unsigned int
-MK::mk_check_for_blctrl(unsigned int count, bool showOutput)
+MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C)
{
+ if (initI2C) {
+ I2C::init();
+ }
+
_retries = 50;
uint8_t foundMotorCount = 0;
@@ -699,7 +705,7 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput)
Motor[i].State |= MOTOR_STATE_PRESENT_MASK; // set present bit;
foundMotorCount++;
- if (Motor[i].MaxPWM == 250) {
+ if ((Motor[i].MaxPWM & 252) == 248) {
Motor[i].Version = BLCTRL_NEW;
} else {
@@ -715,17 +721,17 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput)
fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i, Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature);
}
- if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
- _task_should_exit = true;
+
+ if (!_overrideSecurityChecks) {
+ if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
+ _task_should_exit = true;
+ }
}
}
return foundMotorCount;
}
-
-
-
int
MK::mk_servo_set(unsigned int chan, short val)
{
@@ -738,17 +744,15 @@ MK::mk_servo_set(unsigned int chan, short val)
tmpVal = val;
- if (tmpVal > 1024) {
- tmpVal = 1024;
+ if (tmpVal > 2047) {
+ tmpVal = 2047;
} else if (tmpVal < 0) {
tmpVal = 0;
}
- Motor[chan].SetPoint = (uint8_t)(tmpVal / 4);
- //Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 4;
-
- Motor[chan].SetPointLowerBits = 0;
+ Motor[chan].SetPoint = (uint8_t)(tmpVal >> 3) & 0xff;
+ Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal % 8) & 0x07;
if (_armed == false) {
Motor[chan].SetPoint = 0;
@@ -891,6 +895,7 @@ MK::mk_servo_test(unsigned int chan)
if (_motor >= _num_outputs) {
_motor = -1;
_motortest = false;
+ fprintf(stderr, "[mkblctrl] Motortest finished...\n");
}
}
@@ -954,25 +959,7 @@ MK::ioctl(file *filp, int cmd, unsigned long arg)
{
int ret;
- // XXX disabled, confusing users
-
- /* try it as a GPIO ioctl first */
- ret = gpio_ioctl(filp, cmd, arg);
-
- if (ret != -ENOTTY)
- return ret;
-
- /* if we are in valid PWM mode, try it as a PWM ioctl as well */
- switch (_mode) {
- case MODE_2PWM:
- case MODE_4PWM:
- ret = pwm_ioctl(filp, cmd, arg);
- break;
-
- default:
- debug("not in a PWM mode");
- break;
- }
+ ret = pwm_ioctl(filp, cmd, arg);
/* if nobody wants it, let CDev have it */
if (ret == -ENOTTY)
@@ -1006,7 +993,11 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = OK;
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_GET_UPDATE_RATE:
+ *(uint32_t *)arg = _update_rate;
+ break;
+
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
ret = OK;
break;
@@ -1014,7 +1005,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1):
if (arg < 2150) {
Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg;
- mk_servo_set_value(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 1024));
+ mk_servo_set(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 2047));
} else {
ret = -EINVAL;
@@ -1112,163 +1103,28 @@ ssize_t
MK::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
- // loeschen uint16_t values[4];
uint16_t values[8];
- // loeschen if (count > 4) {
- // loeschen // we only have 4 PWM outputs on the FMU
- // loeschen count = 4;
- // loeschen }
if (count > _num_outputs) {
// we only have 8 I2C outputs in the driver
count = _num_outputs;
}
-
// allow for misaligned values
memcpy(values, buffer, count * 2);
for (uint8_t i = 0; i < count; i++) {
Motor[i].RawPwmValue = (unsigned short)values[i];
- mk_servo_set_value(i, scaling(values[i], 1010, 2100, 0, 1024));
+ mk_servo_set(i, scaling(values[i], 1010, 2100, 0, 2047));
}
return count * 2;
}
-void
-MK::gpio_reset(void)
-{
- /*
- * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
- * to input mode.
- */
- for (unsigned i = 0; i < _ngpio; i++)
- stm32_configgpio(_gpio_tab[i].input);
-
- stm32_gpiowrite(GPIO_GPIO_DIR, 0);
- stm32_configgpio(GPIO_GPIO_DIR);
-}
-
-void
-MK::gpio_set_function(uint32_t gpios, int function)
-{
- /*
- * GPIOs 0 and 1 must have the same direction as they are buffered
- * by a shared 2-port driver. Any attempt to set either sets both.
- */
- if (gpios & 3) {
- gpios |= 3;
-
- /* flip the buffer to output mode if required */
- if (GPIO_SET_OUTPUT == function)
- stm32_gpiowrite(GPIO_GPIO_DIR, 1);
- }
-
- /* configure selected GPIOs as required */
- for (unsigned i = 0; i < _ngpio; i++) {
- if (gpios & (1 << i)) {
- switch (function) {
- case GPIO_SET_INPUT:
- stm32_configgpio(_gpio_tab[i].input);
- break;
-
- case GPIO_SET_OUTPUT:
- stm32_configgpio(_gpio_tab[i].output);
- break;
-
- case GPIO_SET_ALT_1:
- if (_gpio_tab[i].alt != 0)
- stm32_configgpio(_gpio_tab[i].alt);
-
- break;
- }
- }
- }
-
- /* flip buffer to input mode if required */
- if ((GPIO_SET_INPUT == function) && (gpios & 3))
- stm32_gpiowrite(GPIO_GPIO_DIR, 0);
-}
-
-void
-MK::gpio_write(uint32_t gpios, int function)
-{
- int value = (function == GPIO_SET) ? 1 : 0;
-
- for (unsigned i = 0; i < _ngpio; i++)
- if (gpios & (1 << i))
- stm32_gpiowrite(_gpio_tab[i].output, value);
-}
-
-uint32_t
-MK::gpio_read(void)
-{
- uint32_t bits = 0;
-
- for (unsigned i = 0; i < _ngpio; i++)
- if (stm32_gpioread(_gpio_tab[i].input))
- bits |= (1 << i);
-
- return bits;
-}
-
-int
-MK::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int ret = OK;
-
- lock();
-
- switch (cmd) {
-
- case GPIO_RESET:
- gpio_reset();
- break;
-
- case GPIO_SET_OUTPUT:
- case GPIO_SET_INPUT:
- case GPIO_SET_ALT_1:
- gpio_set_function(arg, cmd);
- break;
-
- case GPIO_SET_ALT_2:
- case GPIO_SET_ALT_3:
- case GPIO_SET_ALT_4:
- ret = -EINVAL;
- break;
-
- case GPIO_SET:
- case GPIO_CLEAR:
- gpio_write(arg, cmd);
- break;
-
- case GPIO_GET:
- *(uint32_t *)arg = gpio_read();
- break;
-
- default:
- ret = -ENOTTY;
- }
-
- unlock();
-
- return ret;
-}
namespace
{
-enum PortMode {
- PORT_MODE_UNSET = 0,
- PORT_FULL_GPIO,
- PORT_FULL_SERIAL,
- PORT_FULL_PWM,
- PORT_GPIO_AND_SERIAL,
- PORT_PWM_AND_SERIAL,
- PORT_PWM_AND_GPIO,
-};
-
enum MappingMode {
MAPPING_MK = 0,
MAPPING_PX4,
@@ -1279,58 +1135,11 @@ enum FrameType {
FRAME_X,
};
-PortMode g_port_mode;
int
-mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype)
+mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks)
{
- uint32_t gpio_bits;
int shouldStop = 0;
- MK::Mode servo_mode;
-
- /* reset to all-inputs */
- g_mk->ioctl(0, GPIO_RESET, 0);
-
- gpio_bits = 0;
- servo_mode = MK::MODE_NONE;
-
- switch (new_mode) {
- case PORT_FULL_GPIO:
- case PORT_MODE_UNSET:
- /* nothing more to do here */
- break;
-
- case PORT_FULL_SERIAL:
- /* set all multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_FULL_PWM:
- /* select 4-pin PWM mode */
- servo_mode = MK::MODE_4PWM;
- break;
-
- case PORT_GPIO_AND_SERIAL:
- /* set RX/TX multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_PWM_AND_SERIAL:
- /* select 2-pin PWM mode */
- servo_mode = MK::MODE_2PWM;
- /* set RX/TX multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_PWM_AND_GPIO:
- /* select 2-pin PWM mode */
- servo_mode = MK::MODE_2PWM;
- break;
- }
-
- /* adjust GPIO config for serial mode(s) */
- if (gpio_bits != 0)
- g_mk->ioctl(0, GPIO_SET_ALT_1, gpio_bits);
/* native PX4 addressing) */
g_mk->set_px4mode(px4mode);
@@ -1341,10 +1150,12 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
/* motortest if enabled */
g_mk->set_motor_test(motortest);
+ /* ovveride security checks if enabled */
+ g_mk->set_overrideSecurityChecks(overrideSecurityChecks);
/* count used motors */
do {
- if (g_mk->mk_check_for_blctrl(8, false) != 0) {
+ if (g_mk->mk_check_for_blctrl(8, false, false) != 0) {
shouldStop = 4;
} else {
@@ -1354,41 +1165,55 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
sleep(1);
} while (shouldStop < 3);
- g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true));
-
- /* (re)set the PWM output mode */
- g_mk->set_mode(servo_mode);
+ g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true, false));
-
- if ((servo_mode != MK::MODE_NONE) && (update_rate != 0))
- g_mk->set_pwm_rate(update_rate);
+ g_mk->set_update_rate(update_rate);
return OK;
}
int
-mk_start(unsigned bus, unsigned motors)
+mk_start(unsigned motors, char *device_path)
{
- int ret = OK;
+ int ret;
- if (g_mk == nullptr) {
+ // try i2c3 first
+ g_mk = new MK(3, device_path);
- g_mk = new MK(bus);
+ if (!g_mk)
+ return -ENOMEM;
- if (g_mk == nullptr) {
- ret = -ENOMEM;
+ if (OK == g_mk->init(motors)) {
+ warnx("[mkblctrl] scanning i2c3...\n");
+ ret = g_mk->mk_check_for_blctrl(8, false, true);
- } else {
- ret = g_mk->init(motors);
+ if (ret > 0) {
+ return OK;
+ }
+ }
- if (ret != OK) {
- delete g_mk;
- g_mk = nullptr;
- }
+ delete g_mk;
+ g_mk = nullptr;
+
+ // fallback to bus 1
+ g_mk = new MK(1, device_path);
+
+ if (!g_mk)
+ return -ENOMEM;
+
+ if (OK == g_mk->init(motors)) {
+ warnx("[mkblctrl] scanning i2c1...\n");
+ ret = g_mk->mk_check_for_blctrl(8, false, true);
+
+ if (ret > 0) {
+ return OK;
}
}
- return ret;
+ delete g_mk;
+ g_mk = nullptr;
+
+ return -ENXIO;
}
@@ -1399,33 +1224,21 @@ extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]);
int
mkblctrl_main(int argc, char *argv[])
{
- PortMode port_mode = PORT_FULL_PWM;
int pwm_update_rate_in_hz = UPDATE_RATE;
int motorcount = 8;
- int bus = 1;
int px4mode = MAPPING_PX4;
int frametype = FRAME_PLUS; // + plus is default
bool motortest = false;
+ bool overrideSecurityChecks = false;
bool showHelp = false;
bool newMode = false;
+ char *devicepath = "";
/*
* optional parameters
*/
for (int i = 1; i < argc; i++) {
- /* look for the optional i2c bus parameter */
- if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
- if (argc > i + 1) {
- bus = atoi(argv[i + 1]);
- newMode = true;
-
- } else {
- errx(1, "missing argument for i2c bus (-b)");
- return 1;
- }
- }
-
/* look for the optional frame parameter */
if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) {
if (argc > i + 1) {
@@ -1461,32 +1274,67 @@ mkblctrl_main(int argc, char *argv[])
showHelp = true;
}
+ /* look for the optional --override-security-checks parameter */
+ if (strcmp(argv[i], "--override-security-checks") == 0) {
+ overrideSecurityChecks = true;
+ newMode = true;
+ }
+
+ /* look for the optional device parameter */
+ if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) {
+ if (argc > i + 1) {
+ devicepath = argv[i + 1];
+ newMode = true;
+
+ } else {
+ errx(1, "missing the devicename (-d)");
+ return 1;
+ }
+ }
+
}
if (showHelp) {
fprintf(stderr, "mkblctrl: help:\n");
- fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n");
+ fprintf(stderr, " [-mkmode {+/x}] [-b i2c_bus_number] [-d devicename] [--override-security-checks] [-h / --help]\n\n");
+ fprintf(stderr, "\t -mkmode {+/x} \t\t Type of frame, if Mikrokopter motor order is used.\n");
+ fprintf(stderr, "\t -d {devicepath & name}\t\t Create alternate pwm device.\n");
+ fprintf(stderr, "\t --override-security-checks \t\t Disable all security checks (arming and number of ESCs). Used to test single Motors etc. (DANGER !!!)\n");
+ fprintf(stderr, "\n");
+ fprintf(stderr, "Motortest:\n");
+ fprintf(stderr, "First you have to start mkblctrl, the you can enter Motortest Mode with:\n");
+ fprintf(stderr, "mkblctrl -t\n");
+ fprintf(stderr, "This will spin up once every motor in order of motoraddress. (DANGER !!!)\n");
exit(1);
}
- if (g_mk == nullptr) {
- if (mk_start(bus, motorcount) != OK) {
- errx(1, "failed to start the MK-BLCtrl driver");
+ if (!motortest) {
+ if (g_mk == nullptr) {
+ if (mk_start(motorcount, devicepath) != OK) {
+ errx(1, "failed to start the MK-BLCtrl driver");
+ }
+
+ /* parameter set ? */
+ if (newMode) {
+ /* switch parameter */
+ return mk_new_mode(pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks);
+ }
+
+ exit(0);
} else {
- newMode = true;
+ errx(1, "MK-BLCtrl driver already running");
}
- }
-
- /* parameter set ? */
- if (newMode) {
- /* switch parameter */
- return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype);
- }
+ } else {
+ if (g_mk == nullptr) {
+ errx(1, "MK-BLCtrl driver not running. You have to start it first.");
- /* test, etc. here g*/
+ } else {
+ g_mk->set_motor_test(motortest);
+ exit(0);
- exit(1);
+ }
+ }
}
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index df1958186..ac75682c4 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -35,6 +35,9 @@
* @file mpu6000.cpp
*
* Driver for the Invensense MPU6000 connected via SPI.
+ *
+ * @author Andrew Tridgell
+ * @author Pat Hickey
*/
#include <nuttx/config.h>
@@ -60,16 +63,21 @@
#include <nuttx/arch.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
+#include <drivers/device/ringbuffer.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
+#define MPU_DEVICE_PATH_ACCEL "/dev/mpu6000_accel"
+#define MPU_DEVICE_PATH_GYRO "/dev/mpu6000_gyro"
+
// MPU 6000 registers
#define MPUREG_WHOAMI 0x75
#define MPUREG_SMPLRT_DIV 0x19
@@ -144,6 +152,25 @@
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
+#define MPU6000_ACCEL_DEFAULT_RANGE_G 8
+#define MPU6000_ACCEL_DEFAULT_RATE 1000
+#define MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define MPU6000_GYRO_DEFAULT_RANGE_G 8
+#define MPU6000_GYRO_DEFAULT_RATE 1000
+#define MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ 42
+
+#define MPU6000_ONE_G 9.80665f
+
+/*
+ the MPU6000 can only handle high SPI bus speeds on the sensor and
+ interrupt status registers. All other registers have a maximum 1MHz
+ SPI speed
+ */
+#define MPU6000_LOW_BUS_SPEED 1000*1000
+#define MPU6000_HIGH_BUS_SPEED 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for MPU6K */
class MPU6000_gyro;
@@ -178,20 +205,32 @@ private:
struct hrt_call _call;
unsigned _call_interval;
- struct accel_report _accel_report;
+ RingBuffer *_accel_reports;
+
struct accel_scale _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
+ int _accel_class_instance;
+
+ RingBuffer *_gyro_reports;
- struct gyro_report _gyro_report;
struct gyro_scale _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;
- orb_advert_t _gyro_topic;
- unsigned _reads;
+ unsigned _sample_rate;
+ perf_counter_t _accel_reads;
+ perf_counter_t _gyro_reads;
perf_counter_t _sample_perf;
+ perf_counter_t _bad_transfers;
+
+ math::LowPassFilter2p _accel_filter_x;
+ math::LowPassFilter2p _accel_filter_y;
+ math::LowPassFilter2p _accel_filter_z;
+ math::LowPassFilter2p _gyro_filter_x;
+ math::LowPassFilter2p _gyro_filter_y;
+ math::LowPassFilter2p _gyro_filter_z;
/**
* Start automatic measurement.
@@ -204,6 +243,13 @@ private:
void stop();
/**
+ * Reset chip.
+ *
+ * Resets the chip and measurements ranges, but not scale and offset.
+ */
+ void reset();
+
+ /**
* Static trampoline from the hrt_call context; because we don't have a
* generic hrt wrapper yet.
*
@@ -215,7 +261,7 @@ private:
static void measure_trampoline(void *arg);
/**
- * Fetch measurements from the sensor and update the report ring.
+ * Fetch measurements from the sensor and update the report buffers.
*/
void measure();
@@ -261,17 +307,36 @@ private:
uint16_t swap16(uint16_t val) { return (val >> 8) | (val << 8); }
/**
- * Self test
+ * Measurement self test
*
* @return 0 on success, 1 on failure
*/
int self_test();
+ /**
+ * Accel self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int accel_self_test();
+
+ /**
+ * Gyro self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int gyro_self_test();
+
/*
set low pass filter frequency
*/
void _set_dlpf_filter(uint16_t frequency_hz);
+ /*
+ set sample rate (approximate) - 1kHz to 5Hz
+ */
+ void _set_sample_rate(uint16_t desired_sample_rate_hz);
+
};
/**
@@ -286,30 +351,47 @@ public:
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ virtual int init();
+
protected:
friend class MPU6000;
void parent_poll_notify();
+
private:
MPU6000 *_parent;
+ orb_advert_t _gyro_topic;
+ int _gyro_class_instance;
+
};
/** driver 'main' command */
extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); }
MPU6000::MPU6000(int bus, spi_dev_e device) :
- SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 10000000),
+ SPI("MPU6000", MPU_DEVICE_PATH_ACCEL, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
_gyro(new MPU6000_gyro(this)),
_product(0),
_call_interval(0),
+ _accel_reports(nullptr),
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
+ _accel_class_instance(-1),
+ _gyro_reports(nullptr),
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
- _gyro_topic(-1),
- _reads(0),
- _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read"))
+ _sample_rate(1000),
+ _accel_reads(perf_alloc(PC_COUNT, "mpu6000_accel_read")),
+ _gyro_reads(perf_alloc(PC_COUNT, "mpu6000_gyro_read")),
+ _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
+ _bad_transfers(perf_alloc(PC_COUNT, "mpu6000_bad_transfers")),
+ _accel_filter_x(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_y(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_z(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _gyro_filter_x(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
+ _gyro_filter_y(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
+ _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ)
{
// disable debug() calls
_debug_enabled = false;
@@ -330,8 +412,6 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro_scale.z_offset = 0;
_gyro_scale.z_scale = 1.0f;
- memset(&_accel_report, 0, sizeof(_accel_report));
- memset(&_gyro_report, 0, sizeof(_gyro_report));
memset(&_call, 0, sizeof(_call));
}
@@ -343,8 +423,20 @@ MPU6000::~MPU6000()
/* delete the gyro subdriver */
delete _gyro;
+ /* free any existing reports */
+ if (_accel_reports != nullptr)
+ delete _accel_reports;
+ if (_gyro_reports != nullptr)
+ delete _gyro_reports;
+
+ if (_accel_class_instance != -1)
+ unregister_class_devname(ACCEL_DEVICE_PATH, _accel_class_instance);
+
/* delete the perf counter */
perf_free(_sample_perf);
+ perf_free(_accel_reads);
+ perf_free(_gyro_reads);
+ perf_free(_bad_transfers);
}
int
@@ -361,30 +453,107 @@ MPU6000::init()
return ret;
}
- /* advertise sensor topics */
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report);
- _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report);
+ /* allocate basic report buffers */
+ _accel_reports = new RingBuffer(2, sizeof(accel_report));
+ if (_accel_reports == nullptr)
+ goto out;
+
+ _gyro_reports = new RingBuffer(2, sizeof(gyro_report));
+ if (_gyro_reports == nullptr)
+ goto out;
+
+ reset();
+
+ /* Initialize offsets and scales */
+ _accel_scale.x_offset = 0;
+ _accel_scale.x_scale = 1.0f;
+ _accel_scale.y_offset = 0;
+ _accel_scale.y_scale = 1.0f;
+ _accel_scale.z_offset = 0;
+ _accel_scale.z_scale = 1.0f;
+
+ _gyro_scale.x_offset = 0;
+ _gyro_scale.x_scale = 1.0f;
+ _gyro_scale.y_offset = 0;
+ _gyro_scale.y_scale = 1.0f;
+ _gyro_scale.z_offset = 0;
+ _gyro_scale.z_scale = 1.0f;
+
+ /* do CDev init for the gyro device node, keep it optional */
+ ret = _gyro->init();
+ /* if probe/setup failed, bail now */
+ if (ret != OK) {
+ debug("gyro init failed");
+ return ret;
+ }
+
+ _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH);
+
+ measure();
+
+ if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
+
+ /* measurement will have generated a report, publish */
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+
+ if (_accel_topic < 0)
+ debug("failed to create sensor_accel publication");
+
+ }
+
+ if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _gyro_reports->get(&grp);
+
+ _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+
+ if (_gyro->_gyro_topic < 0)
+ debug("failed to create sensor_gyro publication");
+
+ }
+
+out:
+ return ret;
+}
+
+void MPU6000::reset()
+{
+ // if the mpu6000 is initialised after the l3gd20 and lsm303d
+ // then if we don't do an irqsave/irqrestore here the mpu6000
+ // frequenctly comes up in a bad state where all transfers
+ // come as zero
+ irqstate_t state;
+ state = irqsave();
- // Chip reset
write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
up_udelay(10000);
- // Wake up device and select GyroZ clock (better performance)
+ // Wake up device and select GyroZ clock. Note that the
+ // MPU6000 starts up in sleep mode, and it can take some time
+ // for it to come out of sleep
write_reg(MPUREG_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
up_udelay(1000);
// Disable I2C bus (recommended on datasheet)
write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
+ irqrestore(state);
+
up_udelay(1000);
// SAMPLE RATE
- write_reg(MPUREG_SMPLRT_DIV, 0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz
+ _set_sample_rate(_sample_rate);
usleep(1000);
// FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter)
// was 90 Hz, but this ruins quality and does not improve the
// system response
- _set_dlpf_filter(20);
+ _set_dlpf_filter(MPU6000_DEFAULT_ONCHIP_FILTER_FREQ);
usleep(1000);
// Gyro scale 2000 deg/s ()
write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
@@ -395,12 +564,6 @@ MPU6000::init()
// 2000 deg/s = (2000/180)*PI = 34.906585 rad/s
// scaling factor:
// 1/(2^15)*(2000/180)*PI
- _gyro_scale.x_offset = 0;
- _gyro_scale.x_scale = 1.0f;
- _gyro_scale.y_offset = 0;
- _gyro_scale.y_scale = 1.0f;
- _gyro_scale.z_offset = 0;
- _gyro_scale.z_scale = 1.0f;
_gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F);
_gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F;
@@ -433,14 +596,8 @@ MPU6000::init()
// Correct accel scale factors of 4096 LSB/g
// scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_scale.x_offset = 0;
- _accel_scale.x_scale = 1.0f;
- _accel_scale.y_offset = 0;
- _accel_scale.y_scale = 1.0f;
- _accel_scale.z_offset = 0;
- _accel_scale.z_scale = 1.0f;
- _accel_range_scale = (9.81f / 4096.0f);
- _accel_range_m_s2 = 8.0f * 9.81f;
+ _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
+ _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
usleep(1000);
@@ -454,14 +611,6 @@ MPU6000::init()
// write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
usleep(1000);
- /* do CDev init for the gyro device node, keep it optional */
- int gyro_ret = _gyro->init();
-
- if (gyro_ret != OK) {
- _gyro_topic = -1;
- }
-
- return ret;
}
int
@@ -494,6 +643,19 @@ MPU6000::probe()
}
/*
+ set sample rate (approximate) - 1kHz to 5Hz, for both accel and gyro
+*/
+void
+MPU6000::_set_sample_rate(uint16_t desired_sample_rate_hz)
+{
+ uint8_t div = 1000 / desired_sample_rate_hz;
+ if(div>200) div=200;
+ if(div<1) div=1;
+ write_reg(MPUREG_SMPLRT_DIV, div-1);
+ _sample_rate = 1000 / div;
+}
+
+/*
set the DLPF filter frequency. This affects both accel and gyro.
*/
void
@@ -527,52 +689,132 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
ssize_t
MPU6000::read(struct file *filp, char *buffer, size_t buflen)
{
- int ret = 0;
+ unsigned count = buflen / sizeof(accel_report);
/* buffer must be large enough */
- if (buflen < sizeof(_accel_report))
+ if (count < 1)
return -ENOSPC;
- /* if automatic measurement is not enabled */
- if (_call_interval == 0)
+ /* if automatic measurement is not enabled, get a fresh measurement into the buffer */
+ if (_call_interval == 0) {
+ _accel_reports->flush();
measure();
+ }
- /* copy out the latest reports */
- memcpy(buffer, &_accel_report, sizeof(_accel_report));
- ret = sizeof(_accel_report);
+ /* if no data, error (we could block here) */
+ if (_accel_reports->empty())
+ return -EAGAIN;
- return ret;
+ perf_count(_accel_reads);
+
+ /* copy reports out of our buffer to the caller */
+ accel_report *arp = reinterpret_cast<accel_report *>(buffer);
+ int transferred = 0;
+ while (count--) {
+ if (!_accel_reports->get(arp))
+ break;
+ transferred++;
+ arp++;
+ }
+
+ /* return the number of bytes transferred */
+ return (transferred * sizeof(accel_report));
}
int
MPU6000::self_test()
{
- if (_reads == 0) {
+ if (perf_event_count(_sample_perf) == 0) {
measure();
}
/* return 0 on success, 1 else */
- return (_reads > 0) ? 0 : 1;
+ return (perf_event_count(_sample_perf) > 0) ? 0 : 1;
+}
+
+int
+MPU6000::accel_self_test()
+{
+ if (self_test())
+ return 1;
+
+ /* inspect accel offsets */
+ if (fabsf(_accel_scale.x_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.x_scale - 1.0f) > 0.4f || fabsf(_accel_scale.x_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.y_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.y_scale - 1.0f) > 0.4f || fabsf(_accel_scale.y_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.z_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.z_scale - 1.0f) > 0.4f || fabsf(_accel_scale.z_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ return 0;
+}
+
+int
+MPU6000::gyro_self_test()
+{
+ if (self_test())
+ return 1;
+
+ /* evaluate gyro offsets, complain if offset -> zero or larger than 6 dps */
+ if (fabsf(_gyro_scale.x_offset) > 0.1f || fabsf(_gyro_scale.x_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f)
+ return 1;
+
+ if (fabsf(_gyro_scale.y_offset) > 0.1f || fabsf(_gyro_scale.y_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f)
+ return 1;
+
+ if (fabsf(_gyro_scale.z_offset) > 0.1f || fabsf(_gyro_scale.z_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f)
+ return 1;
+
+ return 0;
}
ssize_t
MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
- int ret = 0;
+ unsigned count = buflen / sizeof(gyro_report);
/* buffer must be large enough */
- if (buflen < sizeof(_gyro_report))
+ if (count < 1)
return -ENOSPC;
- /* if automatic measurement is not enabled */
- if (_call_interval == 0)
+ /* if automatic measurement is not enabled, get a fresh measurement into the buffer */
+ if (_call_interval == 0) {
+ _gyro_reports->flush();
measure();
+ }
- /* copy out the latest report */
- memcpy(buffer, &_gyro_report, sizeof(_gyro_report));
- ret = sizeof(_gyro_report);
+ /* if no data, error (we could block here) */
+ if (_gyro_reports->empty())
+ return -EAGAIN;
- return ret;
+ perf_count(_gyro_reads);
+
+ /* copy reports out of our buffer to the caller */
+ gyro_report *grp = reinterpret_cast<gyro_report *>(buffer);
+ int transferred = 0;
+ while (count--) {
+ if (!_gyro_reports->get(grp))
+ break;
+ transferred++;
+ grp++;
+ }
+
+ /* return the number of bytes transferred */
+ return (transferred * sizeof(gyro_report));
}
int
@@ -580,6 +822,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
case SENSORIOCSPOLLRATE: {
switch (arg) {
@@ -598,9 +844,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
+ return ioctl(filp, SENSORIOCSPOLLRATE, 1000);
+
case SENSOR_POLLRATE_DEFAULT:
- /* XXX 500Hz is just a wild guess */
- return ioctl(filp, SENSORIOCSPOLLRATE, 500);
+ return ioctl(filp, SENSORIOCSPOLLRATE, MPU6000_ACCEL_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
default: {
@@ -614,6 +861,19 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
if (ticks < 1000)
return -EINVAL;
+ // adjust filters
+ float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq();
+ float sample_rate = 1.0e6f/ticks;
+ _accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+ _accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+ _accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+
+
+ float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq();
+ _gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+ _gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+ _gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+
/* update interval for next measurement */
/* XXX this is a bit shady, but no other way to adjust... */
_call.period = _call_interval = ticks;
@@ -633,23 +893,42 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
- case SENSORIOCSQUEUEDEPTH:
- /* XXX not implemented */
- return -EINVAL;
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_accel_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+ irqrestore(flags);
+
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
- /* XXX not implemented */
- return -EINVAL;
+ return _accel_reports->size();
+ case ACCELIOCGSAMPLERATE:
+ return _sample_rate;
case ACCELIOCSSAMPLERATE:
- case ACCELIOCGSAMPLERATE:
- /* XXX not implemented */
- return -EINVAL;
+ _set_sample_rate(arg);
+ return OK;
- case ACCELIOCSLOWPASS:
case ACCELIOCGLOWPASS:
- _set_dlpf_filter((uint16_t)arg);
+ return _accel_filter_x.get_cutoff_freq();
+
+ case ACCELIOCSLOWPASS:
+
+ // XXX decide on relationship of both filters
+ // i.e. disable the on-chip filter
+ //_set_dlpf_filter((uint16_t)arg);
+ _accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
return OK;
case ACCELIOCSSCALE:
@@ -671,15 +950,16 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case ACCELIOCSRANGE:
- case ACCELIOCGRANGE:
/* XXX not implemented */
// XXX change these two values on set:
// _accel_range_scale = (9.81f / 4096.0f);
- // _accel_range_rad_s = 8.0f * 9.81f;
+ // _accel_range_m_s2 = 8.0f * 9.81f;
return -EINVAL;
+ case ACCELIOCGRANGE:
+ return (unsigned long)((_accel_range_m_s2)/MPU6000_ONE_G + 0.5f);
case ACCELIOCSELFTEST:
- return self_test();
+ return accel_self_test();
default:
/* give it to the superclass */
@@ -695,19 +975,42 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
/* these are shared with the accel side */
case SENSORIOCSPOLLRATE:
case SENSORIOCGPOLLRATE:
- case SENSORIOCSQUEUEDEPTH:
- case SENSORIOCGQUEUEDEPTH:
case SENSORIOCRESET:
return ioctl(filp, cmd, arg);
- case GYROIOCSSAMPLERATE:
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ irqstate_t flags = irqsave();
+ if (!_gyro_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _gyro_reports->size();
+
case GYROIOCGSAMPLERATE:
- /* XXX not implemented */
- return -EINVAL;
+ return _sample_rate;
+
+ case GYROIOCSSAMPLERATE:
+ _set_sample_rate(arg);
+ return OK;
- case GYROIOCSLOWPASS:
case GYROIOCGLOWPASS:
- _set_dlpf_filter((uint16_t)arg);
+ return _gyro_filter_x.get_cutoff_freq();
+ case GYROIOCSLOWPASS:
+ _gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ // XXX check relation to the internal lowpass
+ //_set_dlpf_filter((uint16_t)arg);
return OK;
case GYROIOCSSCALE:
@@ -721,15 +1024,16 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case GYROIOCSRANGE:
- case GYROIOCGRANGE:
/* XXX not implemented */
// XXX change these two values on set:
// _gyro_range_scale = xx
- // _gyro_range_m_s2 = xx
+ // _gyro_range_rad_s = xx
return -EINVAL;
+ case GYROIOCGRANGE:
+ return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
case GYROIOCSELFTEST:
- return self_test();
+ return gyro_self_test();
default:
/* give it to the superclass */
@@ -740,9 +1044,10 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
uint8_t
MPU6000::read_reg(unsigned reg)
{
- uint8_t cmd[2];
+ uint8_t cmd[2] = { (uint8_t)(reg | DIR_READ), 0};
- cmd[0] = reg | DIR_READ;
+ // general register transfer at low clock speed
+ set_frequency(MPU6000_LOW_BUS_SPEED);
transfer(cmd, cmd, sizeof(cmd));
@@ -752,9 +1057,10 @@ MPU6000::read_reg(unsigned reg)
uint16_t
MPU6000::read_reg16(unsigned reg)
{
- uint8_t cmd[3];
+ uint8_t cmd[3] = { (uint8_t)(reg | DIR_READ), 0, 0 };
- cmd[0] = reg | DIR_READ;
+ // general register transfer at low clock speed
+ set_frequency(MPU6000_LOW_BUS_SPEED);
transfer(cmd, cmd, sizeof(cmd));
@@ -769,6 +1075,9 @@ MPU6000::write_reg(unsigned reg, uint8_t value)
cmd[0] = reg | DIR_WRITE;
cmd[1] = value;
+ // general register transfer at low clock speed
+ set_frequency(MPU6000_LOW_BUS_SPEED);
+
transfer(cmd, nullptr, sizeof(cmd));
}
@@ -831,6 +1140,10 @@ MPU6000::start()
/* make sure we are stopped first */
stop();
+ /* discard any stale data in the buffers */
+ _accel_reports->flush();
+ _gyro_reports->flush();
+
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&MPU6000::measure_trampoline, this);
}
@@ -844,7 +1157,7 @@ MPU6000::stop()
void
MPU6000::measure_trampoline(void *arg)
{
- MPU6000 *dev = (MPU6000 *)arg;
+ MPU6000 *dev = reinterpret_cast<MPU6000 *>(arg);
/* make another measurement */
dev->measure();
@@ -888,12 +1201,13 @@ MPU6000::measure()
* Fetch the full set of measurements from the MPU6000 in one pass.
*/
mpu_report.cmd = DIR_READ | MPUREG_INT_STATUS;
+
+ // sensor transfer at high clock speed
+ set_frequency(MPU6000_HIGH_BUS_SPEED);
+
if (OK != transfer((uint8_t *)&mpu_report, ((uint8_t *)&mpu_report), sizeof(mpu_report)))
return;
- /* count measurement */
- _reads++;
-
/*
* Convert from big to little endian
*/
@@ -908,6 +1222,20 @@ MPU6000::measure()
report.gyro_y = int16_t_from_bytes(mpu_report.gyro_y);
report.gyro_z = int16_t_from_bytes(mpu_report.gyro_z);
+ if (report.accel_x == 0 &&
+ report.accel_y == 0 &&
+ report.accel_z == 0 &&
+ report.temp == 0 &&
+ report.gyro_x == 0 &&
+ report.gyro_y == 0 &&
+ report.gyro_z == 0) {
+ // all zero data - probably a SPI bus error
+ perf_count(_bad_transfers);
+ perf_end(_sample_perf);
+ return;
+ }
+
+
/*
* Swap axes and negate y
*/
@@ -926,10 +1254,16 @@ MPU6000::measure()
report.gyro_y = gyro_yt;
/*
- * Adjust and scale results to m/s^2.
+ * Report buffers.
*/
- _gyro_report.timestamp = _accel_report.timestamp = hrt_absolute_time();
+ accel_report arb;
+ gyro_report grb;
+ /*
+ * Adjust and scale results to m/s^2.
+ */
+ grb.timestamp = arb.timestamp = hrt_absolute_time();
+ grb.error_count = arb.error_count = 0; // not reported
/*
* 1) Scale raw value to SI units using scaling from datasheet.
@@ -949,40 +1283,57 @@ MPU6000::measure()
/* NOTE: Axes have been swapped to match the board a few lines above. */
- _accel_report.x_raw = report.accel_x;
- _accel_report.y_raw = report.accel_y;
- _accel_report.z_raw = report.accel_z;
+ arb.x_raw = report.accel_x;
+ arb.y_raw = report.accel_y;
+ arb.z_raw = report.accel_z;
- _accel_report.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- _accel_report.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- _accel_report.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
- _accel_report.scaling = _accel_range_scale;
- _accel_report.range_m_s2 = _accel_range_m_s2;
+ float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+
+ arb.x = _accel_filter_x.apply(x_in_new);
+ arb.y = _accel_filter_y.apply(y_in_new);
+ arb.z = _accel_filter_z.apply(z_in_new);
- _accel_report.temperature_raw = report.temp;
- _accel_report.temperature = (report.temp) / 361.0f + 35.0f;
+ arb.scaling = _accel_range_scale;
+ arb.range_m_s2 = _accel_range_m_s2;
- _gyro_report.x_raw = report.gyro_x;
- _gyro_report.y_raw = report.gyro_y;
- _gyro_report.z_raw = report.gyro_z;
+ arb.temperature_raw = report.temp;
+ arb.temperature = (report.temp) / 361.0f + 35.0f;
- _gyro_report.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
- _gyro_report.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
- _gyro_report.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
- _gyro_report.scaling = _gyro_range_scale;
- _gyro_report.range_rad_s = _gyro_range_rad_s;
+ grb.x_raw = report.gyro_x;
+ grb.y_raw = report.gyro_y;
+ grb.z_raw = report.gyro_z;
- _gyro_report.temperature_raw = report.temp;
- _gyro_report.temperature = (report.temp) / 361.0f + 35.0f;
+ float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
+ float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
+ float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
+
+ grb.x = _gyro_filter_x.apply(x_gyro_in_new);
+ grb.y = _gyro_filter_y.apply(y_gyro_in_new);
+ grb.z = _gyro_filter_z.apply(z_gyro_in_new);
+
+ grb.scaling = _gyro_range_scale;
+ grb.range_rad_s = _gyro_range_rad_s;
+
+ grb.temperature_raw = report.temp;
+ grb.temperature = (report.temp) / 361.0f + 35.0f;
+
+ _accel_reports->force(&arb);
+ _gyro_reports->force(&grb);
/* notify anyone waiting for data */
poll_notify(POLLIN);
_gyro->parent_poll_notify();
- /* and publish for subscribers */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report);
- if (_gyro_topic != -1) {
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report);
+ if (_accel_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
+ }
+
+ if (_gyro->_gyro_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb);
}
/* stop measuring */
@@ -992,17 +1343,45 @@ MPU6000::measure()
void
MPU6000::print_info()
{
- printf("reads: %u\n", _reads);
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_accel_reads);
+ perf_print_counter(_gyro_reads);
+ _accel_reports->print_info("accel queue");
+ _gyro_reports->print_info("gyro queue");
}
MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) :
- CDev("MPU6000_gyro", GYRO_DEVICE_PATH),
- _parent(parent)
+ CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO),
+ _parent(parent),
+ _gyro_topic(-1),
+ _gyro_class_instance(-1)
{
}
MPU6000_gyro::~MPU6000_gyro()
{
+ if (_gyro_class_instance != -1)
+ unregister_class_devname(GYRO_DEVICE_PATH, _gyro_class_instance);
+}
+
+int
+MPU6000_gyro::init()
+{
+ int ret;
+
+ // do base class init
+ ret = CDev::init();
+
+ /* if probe/setup failed, bail now */
+ if (ret != OK) {
+ debug("gyro init failed");
+ return ret;
+ }
+
+ _gyro_class_instance = register_class_devname(GYRO_DEVICE_PATH);
+
+out:
+ return ret;
}
void
@@ -1045,7 +1424,8 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
/* create the driver */
g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU);
@@ -1057,7 +1437,7 @@ start()
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1065,6 +1445,8 @@ start()
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
goto fail;
+ close(fd);
+
exit(0);
fail:
@@ -1084,24 +1466,22 @@ fail:
void
test()
{
- int fd = -1;
- int fd_gyro = -1;
- struct accel_report a_report;
- struct gyro_report g_report;
+ accel_report a_report;
+ gyro_report g_report;
ssize_t sz;
/* get the driver */
- fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
- ACCEL_DEVICE_PATH);
+ MPU_DEVICE_PATH_ACCEL);
/* get the driver */
- fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
+ int fd_gyro = open(MPU_DEVICE_PATH_GYRO, O_RDONLY);
if (fd_gyro < 0)
- err(1, "%s open failed", GYRO_DEVICE_PATH);
+ err(1, "%s open failed", MPU_DEVICE_PATH_GYRO);
/* reset to manual polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@@ -1110,8 +1490,10 @@ test()
/* do a simple demand read */
sz = read(fd, &a_report, sizeof(a_report));
- if (sz != sizeof(a_report))
+ if (sz != sizeof(a_report)) {
+ warnx("ret: %d, expected: %d", sz, sizeof(a_report));
err(1, "immediate acc read failed");
+ }
warnx("single read");
warnx("time: %lld", a_report.timestamp);
@@ -1122,13 +1504,15 @@ test()
warnx("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
warnx("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
- (double)(a_report.range_m_s2 / 9.81f));
+ (double)(a_report.range_m_s2 / MPU6000_ONE_G));
/* do a simple demand read */
sz = read(fd_gyro, &g_report, sizeof(g_report));
- if (sz != sizeof(g_report))
+ if (sz != sizeof(g_report)) {
+ warnx("ret: %d, expected: %d", sz, sizeof(g_report));
err(1, "immediate gyro read failed");
+ }
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
@@ -1155,7 +1539,7 @@ test()
void
reset()
{
- int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1166,6 +1550,8 @@ reset()
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
err(1, "driver poll restart failed");
+ close(fd);
+
exit(0);
}
diff --git a/src/drivers/ms5611/module.mk b/src/drivers/ms5611/module.mk
index 3c4b0f093..20f8aa173 100644
--- a/src/drivers/ms5611/module.mk
+++ b/src/drivers/ms5611/module.mk
@@ -37,4 +37,4 @@
MODULE_COMMAND = ms5611
-SRCS = ms5611.cpp
+SRCS = ms5611.cpp ms5611_spi.cpp ms5611_i2c.cpp
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 59ab5936e..0ef056273 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -33,13 +33,11 @@
/**
* @file ms5611.cpp
- * Driver for the MS5611 barometric pressure sensor connected via I2C.
+ * Driver for the MS5611 barometric pressure sensor connected via I2C or SPI.
*/
#include <nuttx/config.h>
-#include <drivers/device/i2c.h>
-
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
@@ -59,12 +57,15 @@
#include <arch/board/board.h>
+#include <drivers/device/device.h>
+#include <drivers/drv_baro.h>
#include <drivers/drv_hrt.h>
+#include <drivers/device/ringbuffer.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
-#include <drivers/drv_baro.h>
+#include "ms5611.h"
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -76,35 +77,26 @@ static const int ERROR = -1;
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
-/**
- * Calibration PROM as reported by the device.
- */
-#pragma pack(push,1)
-struct ms5611_prom_s {
- uint16_t factory_setup;
- uint16_t c1_pressure_sens;
- uint16_t c2_pressure_offset;
- uint16_t c3_temp_coeff_pres_sens;
- uint16_t c4_temp_coeff_pres_offset;
- uint16_t c5_reference_temp;
- uint16_t c6_temp_coeff_temp;
- uint16_t serial_and_crc;
-};
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { __typeof__(_x) _tmp = _x+1; if (_tmp >= _lim) _tmp = 0; _x = _tmp; } while(0)
-/**
- * Grody hack for crc4()
+/* helper macro for arithmetic - returns the square of the argument */
+#define POW2(_x) ((_x) * (_x))
+
+/*
+ * MS5611 internal constants and data structures.
*/
-union ms5611_prom_u {
- uint16_t c[8];
- struct ms5611_prom_s s;
-};
-#pragma pack(pop)
-class MS5611 : public device::I2C
+/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
+#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
+#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
+#define MS5611_BARO_DEVICE_PATH "/dev/ms5611"
+
+class MS5611 : public device::CDev
{
public:
- MS5611(int bus);
- virtual ~MS5611();
+ MS5611(device::Device *interface, ms5611::prom_u &prom_buf);
+ ~MS5611();
virtual int init();
@@ -117,18 +109,14 @@ public:
void print_info();
protected:
- virtual int probe();
+ Device *_interface;
-private:
- union ms5611_prom_u _prom;
+ ms5611::prom_s _prom;
struct work_s _work;
unsigned _measure_ticks;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- struct baro_report *_reports;
+ RingBuffer *_reports;
bool _collect_phase;
unsigned _measure_phase;
@@ -137,28 +125,23 @@ private:
int32_t _TEMP;
int64_t _OFF;
int64_t _SENS;
+ float _P;
+ float _T;
/* altitude conversion calibration */
unsigned _msl_pressure; /* in kPa */
orb_advert_t _baro_topic;
+ int _class_instance;
+
perf_counter_t _sample_perf;
perf_counter_t _measure_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.
+ * Initialize 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.
@@ -198,74 +181,24 @@ private:
*
* @return OK if the measurement command was successful.
*/
- int measure();
+ virtual int measure();
/**
* Collect the result of the most recent measurement.
*/
- int collect();
-
- /**
- * Send a reset command to the MS5611.
- *
- * This is required after any bus reset.
- */
- int cmd_reset();
-
- /**
- * Read the MS5611 PROM
- *
- * @return OK if the PROM reads successfully.
- */
- int read_prom();
-
- /**
- * PROM CRC routine ported from MS5611 application note
- *
- * @param n_prom Pointer to words read from PROM.
- * @return True if the CRC matches.
- */
- bool crc4(uint16_t *n_prom);
-
+ virtual int collect();
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
-/* helper macro for arithmetic - returns the square of the argument */
-#define POW2(_x) ((_x) * (_x))
-
-/*
- * MS5611 internal constants and data structures.
- */
-
-/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
-#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
-#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
-
-#define MS5611_BUS PX4_I2C_BUS_ONBOARD
-#define MS5611_ADDRESS_1 PX4_I2C_OBDEV_MS5611 /* address select pins pulled high (PX4FMU series v1.6+) */
-#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
-
-#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 */
-
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int ms5611_main(int argc, char *argv[]);
-
-MS5611::MS5611(int bus) :
- I2C("MS5611", BARO_DEVICE_PATH, bus, 0, 400000),
+MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf) :
+ CDev("MS5611", MS5611_BARO_DEVICE_PATH),
+ _interface(interface),
+ _prom(prom_buf.s),
_measure_ticks(0),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
_reports(nullptr),
_collect_phase(false),
_measure_phase(0),
@@ -274,15 +207,13 @@ MS5611::MS5611(int bus) :
_SENS(0),
_msl_pressure(101325),
_baro_topic(-1),
+ _class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")),
_measure_perf(perf_alloc(PC_ELAPSED, "ms5611_measure")),
_comms_errors(perf_alloc(PC_COUNT, "ms5611_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "ms5611_buffer_overflows"))
{
- // enable debug() calls
- _debug_enabled = true;
-
- // work_cancel in the dtor will explode if we don't do this...
+ // work_cancel in stop_cycle called from the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -291,80 +222,102 @@ MS5611::~MS5611()
/* make sure we are truly inactive */
stop_cycle();
+ if (_class_instance != -1)
+ unregister_class_devname(MS5611_BARO_DEVICE_PATH, _class_instance);
+
/* free any existing reports */
if (_reports != nullptr)
- delete[] _reports;
+ delete _reports;
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_measure_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
+
+ delete _interface;
}
int
MS5611::init()
{
- int ret = ERROR;
+ int ret;
- /* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ ret = CDev::init();
+ if (ret != OK) {
+ debug("CDev init failed");
goto out;
+ }
/* allocate basic report buffers */
- _num_reports = 2;
- _reports = new struct baro_report[_num_reports];
+ _reports = new RingBuffer(2, sizeof(baro_report));
- if (_reports == nullptr)
+ if (_reports == nullptr) {
+ debug("can't get memory for reports");
+ ret = -ENOMEM;
goto out;
+ }
- _oldest_report = _next_report = 0;
+ /* register alternate interfaces if we have to */
+ _class_instance = register_class_devname(BARO_DEVICE_PATH);
- /* get a publish handle on the baro topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _baro_topic = orb_advertise(ORB_ID(sensor_baro), &_reports[0]);
+ struct baro_report brp;
+ /* do a first measurement cycle to populate reports with valid data */
+ _measure_phase = 0;
+ _reports->flush();
- if (_baro_topic < 0)
- debug("failed to create sensor_baro object");
+ /* this do..while is goto without goto */
+ do {
+ /* do temperature first */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
- ret = OK;
-out:
- return ret;
-}
+ usleep(MS5611_CONVERSION_INTERVAL);
-int
-MS5611::probe()
-{
- _retries = 10;
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
- if ((OK == probe_address(MS5611_ADDRESS_1)) ||
- (OK == probe_address(MS5611_ADDRESS_2))) {
- /*
- * Disable retries; we may enable them selectively in some cases,
- * but the device gets confused if we retry some of the commands.
- */
- _retries = 0;
- return OK;
- }
+ /* now do a pressure measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
- return -EIO;
-}
+ usleep(MS5611_CONVERSION_INTERVAL);
-int
-MS5611::probe_address(uint8_t address)
-{
- /* select the address we are going to try */
- set_address(address);
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
- /* send reset command */
- if (OK != cmd_reset())
- return -EIO;
+ /* state machine will have generated a report, copy it out */
+ _reports->get(&brp);
- /* read PROM */
- if (OK != read_prom())
- return -EIO;
+ ret = OK;
- return OK;
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+
+ _baro_topic = orb_advertise(ORB_ID(sensor_baro), &brp);
+
+ if (_baro_topic < 0)
+ debug("failed to create sensor_baro publication");
+ }
+
+ } while (0);
+
+out:
+ return ret;
}
ssize_t
MS5611::read(struct file *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(struct baro_report);
+ struct baro_report *brp = reinterpret_cast<struct baro_report *>(buffer);
int ret = 0;
/* buffer must be large enough */
@@ -380,10 +333,9 @@ MS5611::read(struct file *filp, char *buffer, size_t buflen)
* 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 (_reports->get(brp)) {
+ ret += sizeof(*brp);
+ brp++;
}
}
@@ -392,10 +344,9 @@ MS5611::read(struct file *filp, char *buffer, size_t buflen)
}
/* manual measurement - run one conversion */
- /* XXX really it'd be nice to lock against other readers here */
do {
_measure_phase = 0;
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* do temperature first */
if (OK != measure()) {
@@ -424,8 +375,8 @@ MS5611::read(struct file *filp, char *buffer, size_t buflen)
}
/* state machine will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
+ if (_reports->get(brp))
+ ret = sizeof(*brp);
} while (0);
@@ -500,35 +451,28 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
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 baro_report *buf = new struct baro_report[arg];
-
- if (nullptr == buf)
- return -ENOMEM;
-
- /* reset the measurement state machine with the new buffer, free the old */
- stop_cycle();
- delete[] _reports;
- _num_reports = arg;
- _reports = buf;
- start_cycle();
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
- return OK;
+ irqstate_t flags = irqsave();
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
}
+ irqrestore(flags);
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
+ return _reports->size();
case SENSORIOCRESET:
- /* XXX implement this */
- return -EINVAL;
+ /*
+ * Since we are initialized, we do not need to do anything, since the
+ * PROM is correctly read and the part does not need to be configured.
+ */
+ return OK;
case BAROIOCSMSLPRESSURE:
@@ -546,8 +490,9 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
break;
}
- /* give it to the superclass */
- return I2C::ioctl(filp, cmd, arg);
+ /* give it to the bus-specific superclass */
+ // return bus_ioctl(filp, cmd, arg);
+ return CDev::ioctl(filp, cmd, arg);
}
void
@@ -557,7 +502,7 @@ MS5611::start_cycle()
/* reset the report ring and state machine */
_collect_phase = false;
_measure_phase = 0;
- _oldest_report = _next_report = 0;
+ _reports->flush();
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&MS5611::cycle_trampoline, this, 1);
@@ -572,7 +517,7 @@ MS5611::stop_cycle()
void
MS5611::cycle_trampoline(void *arg)
{
- MS5611 *dev = (MS5611 *)arg;
+ MS5611 *dev = reinterpret_cast<MS5611 *>(arg);
dev->cycle();
}
@@ -592,7 +537,7 @@ MS5611::cycle()
/*
* The ms5611 seems to regularly fail to respond to
* its address; this happens often enough that we'd rather not
- * spam the console with the message.
+ * spam the console with a message for this.
*/
} else {
//log("collection error %d", ret);
@@ -654,17 +599,12 @@ MS5611::measure()
/*
* In phase zero, request temperature; in other phases, request pressure.
*/
- uint8_t cmd_data = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
+ unsigned addr = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
/*
* Send the command to begin measuring.
- *
- * Disable retries on this command; we can't know whether failure
- * means the device did or did not see the write.
*/
- _retries = 0;
- ret = transfer(&cmd_data, 1, nullptr, 0);
-
+ ret = _interface->ioctl(IOCTL_MEASURE, addr);
if (OK != ret)
perf_count(_comms_errors);
@@ -677,47 +617,35 @@ int
MS5611::collect()
{
int ret;
- uint8_t cmd;
- uint8_t data[3];
- union {
- uint8_t b[4];
- uint32_t w;
- } cvt;
-
- /* read the most recent measurement */
- cmd = 0;
+ uint32_t raw;
perf_begin(_sample_perf);
+ struct baro_report report;
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
- _reports[_next_report].timestamp = hrt_absolute_time();
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
- ret = transfer(&cmd, 1, &data[0], 3);
- if (ret != OK) {
+ /* read the most recent measurement - read offset/size are hardcoded in the interface */
+ ret = _interface->read(0, (void *)&raw, 0);
+ if (ret < 0) {
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
}
- /* fetch the raw value */
- cvt.b[0] = data[2];
- cvt.b[1] = data[1];
- cvt.b[2] = data[0];
- cvt.b[3] = 0;
- uint32_t raw = cvt.w;
-
/* handle a measurement */
if (_measure_phase == 0) {
/* temperature offset (in ADC units) */
- int32_t dT = (int32_t)raw - ((int32_t)_prom.s.c5_reference_temp << 8);
+ int32_t dT = (int32_t)raw - ((int32_t)_prom.c5_reference_temp << 8);
/* absolute temperature in centidegrees - note intermediate value is outside 32-bit range */
- _TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.s.c6_temp_coeff_temp) >> 23);
+ _TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.c6_temp_coeff_temp) >> 23);
/* base sensor scale/offset values */
- _SENS = ((int64_t)_prom.s.c1_pressure_sens << 15) + (((int64_t)_prom.s.c3_temp_coeff_pres_sens * dT) >> 8);
- _OFF = ((int64_t)_prom.s.c2_pressure_offset << 16) + (((int64_t)_prom.s.c4_temp_coeff_pres_offset * dT) >> 7);
+ _SENS = ((int64_t)_prom.c1_pressure_sens << 15) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 8);
+ _OFF = ((int64_t)_prom.c2_pressure_offset << 16) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 7);
/* temperature compensation */
if (_TEMP < 2000) {
@@ -743,10 +671,12 @@ MS5611::collect()
/* pressure calculation, result in Pa */
int32_t P = (((raw * _SENS) >> 21) - _OFF) >> 15;
+ _P = P * 0.01f;
+ _T = _TEMP * 0.01f;
/* generate a new report */
- _reports[_next_report].temperature = _TEMP / 100.0f;
- _reports[_next_report].pressure = P / 100.0f; /* convert to millibar */
+ report.temperature = _TEMP / 100.0f;
+ report.pressure = P / 100.0f; /* convert to millibar */
/* altitude calculations based on http://www.kansasflyer.org/index.asp?nav=Avi&sec=Alti&tab=Theory&pg=1 */
@@ -761,30 +691,7 @@ MS5611::collect()
* double precision: ms5611_read: 992 events, 258641us elapsed, min 202us max 305us
* single precision: ms5611_read: 963 events, 208066us elapsed, min 202us max 241us
*/
-#if 0/* USE_FLOAT */
- /* tropospheric properties (0-11km) for standard atmosphere */
- const float T1 = 15.0f + 273.15f; /* temperature at base height in Kelvin */
- const float a = -6.5f / 1000f; /* temperature gradient in degrees per metre */
- const float g = 9.80665f; /* gravity constant in m/s/s */
- const float R = 287.05f; /* ideal gas constant in J/kg/K */
-
- /* current pressure at MSL in kPa */
- float p1 = _msl_pressure / 1000.0f;
- /* measured pressure in kPa */
- float p = P / 1000.0f;
-
- /*
- * Solve:
- *
- * / -(aR / g) \
- * | (p / p1) . T1 | - T1
- * \ /
- * h = ------------------------------- + h1
- * a
- */
- _reports[_next_report].altitude = (((powf((p / p1), (-(a * R) / g))) * T1) - T1) / a;
-#else
/* tropospheric properties (0-11km) for standard atmosphere */
const double T1 = 15.0 + 273.15; /* temperature at base height in Kelvin */
const double a = -6.5 / 1000; /* temperature gradient in degrees per metre */
@@ -806,18 +713,16 @@ MS5611::collect()
* h = ------------------------------- + h1
* a
*/
- _reports[_next_report].altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
-#endif
- /* publish it */
- orb_publish(ORB_ID(sensor_baro), _baro_topic, &_reports[_next_report]);
+ report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
- /* post a report to the ring - note, not locked */
- INCREMENT(_next_report, _num_reports);
+ /* publish it */
+ if (_baro_topic > 0 && !(_pub_blocked)) {
+ /* publish it */
+ orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
+ }
- /* if we are running up against the oldest report, toss it */
- if (_next_report == _oldest_report) {
+ if (_reports->force(&report)) {
perf_count(_buffer_overflows);
- INCREMENT(_oldest_report, _num_reports);
}
/* notify anyone waiting for data */
@@ -832,55 +737,50 @@ MS5611::collect()
return OK;
}
-int
-MS5611::cmd_reset()
+void
+MS5611::print_info()
{
- unsigned old_retrycount = _retries;
- uint8_t cmd = ADDR_RESET_CMD;
- int result;
-
- /* bump the retry count */
- _retries = 10;
- result = transfer(&cmd, 1, nullptr, 0);
- _retries = old_retrycount;
+ 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");
+ printf("TEMP: %d\n", _TEMP);
+ printf("SENS: %lld\n", _SENS);
+ printf("OFF: %lld\n", _OFF);
+ printf("P: %.3f\n", _P);
+ printf("T: %.3f\n", _T);
+ printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
- return result;
+ printf("factory_setup %u\n", _prom.factory_setup);
+ printf("c1_pressure_sens %u\n", _prom.c1_pressure_sens);
+ printf("c2_pressure_offset %u\n", _prom.c2_pressure_offset);
+ printf("c3_temp_coeff_pres_sens %u\n", _prom.c3_temp_coeff_pres_sens);
+ printf("c4_temp_coeff_pres_offset %u\n", _prom.c4_temp_coeff_pres_offset);
+ printf("c5_reference_temp %u\n", _prom.c5_reference_temp);
+ printf("c6_temp_coeff_temp %u\n", _prom.c6_temp_coeff_temp);
+ printf("serial_and_crc %u\n", _prom.serial_and_crc);
}
-int
-MS5611::read_prom()
+/**
+ * Local functions in support of the shell command.
+ */
+namespace ms5611
{
- uint8_t prom_buf[2];
- union {
- uint8_t b[2];
- uint16_t w;
- } cvt;
-
- /*
- * Wait for PROM contents to be in the device (2.8 ms) in the case we are
- * called immediately after reset.
- */
- usleep(3000);
- /* read and convert PROM words */
- for (int i = 0; i < 8; i++) {
- uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
-
- if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
- break;
-
- /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
- cvt.b[0] = prom_buf[1];
- cvt.b[1] = prom_buf[0];
- _prom.c[i] = cvt.w;
- }
+MS5611 *g_dev;
- /* calculate CRC and return success/failure accordingly */
- return crc4(&_prom.c[0]) ? OK : -EIO;
-}
+void start();
+void test();
+void reset();
+void info();
+void calibrate(unsigned altitude);
+/**
+ * MS5611 crc4 cribbed from the datasheet
+ */
bool
-MS5611::crc4(uint16_t *n_prom)
+crc4(uint16_t *n_prom)
{
int16_t cnt;
uint16_t n_rem;
@@ -922,43 +822,6 @@ MS5611::crc4(uint16_t *n_prom)
return (0x000F & crc_read) == (n_rem ^ 0x00);
}
-void
-MS5611::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);
- printf("TEMP: %d\n", _TEMP);
- printf("SENS: %lld\n", _SENS);
- printf("OFF: %lld\n", _OFF);
- printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
-
- printf("factory_setup %u\n", _prom.s.factory_setup);
- printf("c1_pressure_sens %u\n", _prom.s.c1_pressure_sens);
- printf("c2_pressure_offset %u\n", _prom.s.c2_pressure_offset);
- printf("c3_temp_coeff_pres_sens %u\n", _prom.s.c3_temp_coeff_pres_sens);
- printf("c4_temp_coeff_pres_offset %u\n", _prom.s.c4_temp_coeff_pres_offset);
- printf("c5_reference_temp %u\n", _prom.s.c5_reference_temp);
- printf("c6_temp_coeff_temp %u\n", _prom.s.c6_temp_coeff_temp);
- printf("serial_and_crc %u\n", _prom.s.serial_and_crc);
-}
-
-/**
- * Local functions in support of the shell command.
- */
-namespace ms5611
-{
-
-MS5611 *g_dev;
-
-void start();
-void test();
-void reset();
-void info();
-void calibrate(unsigned altitude);
/**
* Start the driver.
@@ -967,27 +830,46 @@ void
start()
{
int fd;
+ prom_u prom_buf;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
- /* create the driver */
- g_dev = new MS5611(MS5611_BUS);
+ device::Device *interface = nullptr;
- if (g_dev == nullptr)
- goto fail;
+ /* create the driver, try SPI first, fall back to I2C if unsuccessful */
+ if (MS5611_spi_interface != nullptr)
+ interface = MS5611_spi_interface(prom_buf);
+ if (interface == nullptr && (MS5611_i2c_interface != nullptr))
+ interface = MS5611_i2c_interface(prom_buf);
- if (OK != g_dev->init())
- goto fail;
+ if (interface == nullptr)
+ errx(1, "failed to allocate an interface");
- /* set the poll rate to default, starts automatic data collection */
- fd = open(BARO_DEVICE_PATH, O_RDONLY);
+ if (interface->init() != OK) {
+ delete interface;
+ errx(1, "interface init failed");
+ }
- if (fd < 0)
+ g_dev = new MS5611(interface, prom_buf);
+ if (g_dev == nullptr) {
+ delete interface;
+ errx(1, "failed to allocate driver");
+ }
+ if (g_dev->init() != OK)
goto fail;
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
+ if (fd < 0) {
+ warnx("can't open baro device");
goto fail;
+ }
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ warnx("failed setting default poll rate");
+ goto fail;
+ }
exit(0);
@@ -1013,10 +895,10 @@ test()
ssize_t sz;
int ret;
- int fd = open(BARO_DEVICE_PATH, O_RDONLY);
+ int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", BARO_DEVICE_PATH);
+ err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH);
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -1072,7 +954,7 @@ test()
void
reset()
{
- int fd = open(BARO_DEVICE_PATH, O_RDONLY);
+ int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1111,10 +993,10 @@ calibrate(unsigned altitude)
float pressure;
float p1;
- int fd = open(BARO_DEVICE_PATH, O_RDONLY);
+ int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", BARO_DEVICE_PATH);
+ err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH);
/* start the sensor polling at max */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX))
@@ -1154,11 +1036,11 @@ calibrate(unsigned altitude)
const float g = 9.80665f; /* gravity constant in m/s/s */
const float R = 287.05f; /* ideal gas constant in J/kg/K */
- warnx("averaged pressure %10.4fkPa at %um", pressure, altitude);
+ warnx("averaged pressure %10.4fkPa at %um", (double)pressure, altitude);
p1 = pressure * (powf(((T1 + (a * (float)altitude)) / T1), (g / (a * R))));
- warnx("calculated MSL pressure %10.4fkPa", p1);
+ warnx("calculated MSL pressure %10.4fkPa", (double)p1);
/* save as integer Pa */
p1 *= 1000.0f;
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
new file mode 100644
index 000000000..76fb84de8
--- /dev/null
+++ b/src/drivers/ms5611/ms5611.h
@@ -0,0 +1,85 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-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 ms5611.h
+ *
+ * Shared defines for the ms5611 driver.
+ */
+
+#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 */
+
+/* interface ioctls */
+#define IOCTL_RESET 2
+#define IOCTL_MEASURE 3
+
+namespace ms5611
+{
+
+/**
+ * Calibration PROM as reported by the device.
+ */
+#pragma pack(push,1)
+struct prom_s {
+ uint16_t factory_setup;
+ uint16_t c1_pressure_sens;
+ uint16_t c2_pressure_offset;
+ uint16_t c3_temp_coeff_pres_sens;
+ uint16_t c4_temp_coeff_pres_offset;
+ uint16_t c5_reference_temp;
+ uint16_t c6_temp_coeff_temp;
+ uint16_t serial_and_crc;
+};
+
+/**
+ * Grody hack for crc4()
+ */
+union prom_u {
+ uint16_t c[8];
+ prom_s s;
+};
+#pragma pack(pop)
+
+extern bool crc4(uint16_t *n_prom);
+
+} /* namespace */
+
+/* interface factories */
+extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf) weak_function;
+extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf) weak_function;
+
diff --git a/src/drivers/ms5611/ms5611_i2c.cpp b/src/drivers/ms5611/ms5611_i2c.cpp
new file mode 100644
index 000000000..87d9b94a6
--- /dev/null
+++ b/src/drivers/ms5611/ms5611_i2c.cpp
@@ -0,0 +1,278 @@
+/****************************************************************************
+ *
+ * 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 ms5611_i2c.cpp
+ *
+ * I2C interface for MS5611
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/i2c.h>
+
+#include "ms5611.h"
+
+#include "board_config.h"
+
+#ifdef PX4_I2C_OBDEV_MS5611
+
+#ifndef PX4_I2C_BUS_ONBOARD
+ #define MS5611_BUS 1
+#else
+ #define MS5611_BUS PX4_I2C_BUS_ONBOARD
+#endif
+
+#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
+#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
+
+
+
+device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf);
+
+class MS5611_I2C : public device::I2C
+{
+public:
+ MS5611_I2C(int bus, ms5611::prom_u &prom_buf);
+ virtual ~MS5611_I2C();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+protected:
+ virtual int probe();
+
+private:
+ ms5611::prom_u &_prom;
+
+ int _probe_address(uint8_t address);
+
+ /**
+ * Send a reset command to the MS5611.
+ *
+ * This is required after any bus reset.
+ */
+ int _reset();
+
+ /**
+ * Send a measure command to the MS5611.
+ *
+ * @param addr Which address to use for the measure operation.
+ */
+ int _measure(unsigned addr);
+
+ /**
+ * Read the MS5611 PROM
+ *
+ * @return OK if the PROM reads successfully.
+ */
+ int _read_prom();
+
+};
+
+device::Device *
+MS5611_i2c_interface(ms5611::prom_u &prom_buf)
+{
+ return new MS5611_I2C(MS5611_BUS, prom_buf);
+}
+
+MS5611_I2C::MS5611_I2C(int bus, ms5611::prom_u &prom) :
+ I2C("MS5611_I2C", nullptr, bus, 0, 400000),
+ _prom(prom)
+{
+}
+
+MS5611_I2C::~MS5611_I2C()
+{
+}
+
+int
+MS5611_I2C::init()
+{
+ /* this will call probe(), and thereby _probe_address */
+ return I2C::init();
+}
+
+int
+MS5611_I2C::read(unsigned offset, void *data, unsigned count)
+{
+ union _cvt {
+ uint8_t b[4];
+ uint32_t w;
+ } *cvt = (_cvt *)data;
+ uint8_t buf[3];
+
+ /* read the most recent measurement */
+ uint8_t cmd = 0;
+ int ret = transfer(&cmd, 1, &buf[0], 3);
+ if (ret == OK) {
+ /* fetch the raw value */
+ cvt->b[0] = buf[2];
+ cvt->b[1] = buf[1];
+ cvt->b[2] = buf[0];
+ cvt->b[3] = 0;
+ }
+
+ return ret;
+}
+
+int
+MS5611_I2C::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+ case IOCTL_RESET:
+ ret = _reset();
+ break;
+
+ case IOCTL_MEASURE:
+ ret = _measure(arg);
+ break;
+
+ default:
+ ret = EINVAL;
+ }
+
+ return ret;
+}
+
+int
+MS5611_I2C::probe()
+{
+ _retries = 10;
+
+ if ((OK == _probe_address(MS5611_ADDRESS_1)) ||
+ (OK == _probe_address(MS5611_ADDRESS_2))) {
+ /*
+ * Disable retries; we may enable them selectively in some cases,
+ * but the device gets confused if we retry some of the commands.
+ */
+ _retries = 0;
+ return OK;
+ }
+
+ return -EIO;
+}
+
+int
+MS5611_I2C::_probe_address(uint8_t address)
+{
+ /* select the address we are going to try */
+ set_address(address);
+
+ /* send reset command */
+ if (OK != _reset())
+ return -EIO;
+
+ /* read PROM */
+ if (OK != _read_prom())
+ return -EIO;
+
+ return OK;
+}
+
+
+int
+MS5611_I2C::_reset()
+{
+ unsigned old_retrycount = _retries;
+ uint8_t cmd = ADDR_RESET_CMD;
+ int result;
+
+ /* bump the retry count */
+ _retries = 10;
+ result = transfer(&cmd, 1, nullptr, 0);
+ _retries = old_retrycount;
+
+ return result;
+}
+
+int
+MS5611_I2C::_measure(unsigned addr)
+{
+ /*
+ * Disable retries on this command; we can't know whether failure
+ * means the device did or did not see the command.
+ */
+ _retries = 0;
+
+ uint8_t cmd = addr;
+ return transfer(&cmd, 1, nullptr, 0);
+}
+
+int
+MS5611_I2C::_read_prom()
+{
+ uint8_t prom_buf[2];
+ union {
+ uint8_t b[2];
+ uint16_t w;
+ } cvt;
+
+ /*
+ * Wait for PROM contents to be in the device (2.8 ms) in the case we are
+ * called immediately after reset.
+ */
+ usleep(3000);
+
+ /* read and convert PROM words */
+ for (int i = 0; i < 8; i++) {
+ uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
+
+ if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
+ break;
+
+ /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
+ cvt.b[0] = prom_buf[1];
+ cvt.b[1] = prom_buf[0];
+ _prom.c[i] = cvt.w;
+ }
+
+ /* calculate CRC and return success/failure accordingly */
+ return ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
+}
+
+#endif /* PX4_I2C_OBDEV_MS5611 */
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
new file mode 100644
index 000000000..26216e840
--- /dev/null
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -0,0 +1,276 @@
+/****************************************************************************
+ *
+ * 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 ms5611_spi.cpp
+ *
+ * SPI interface for MS5611
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/spi.h>
+
+#include "ms5611.h"
+#include "board_config.h"
+
+/* SPI protocol address bits */
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#ifdef PX4_SPIDEV_BARO
+
+device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf);
+
+class MS5611_SPI : public device::SPI
+{
+public:
+ MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf);
+ virtual ~MS5611_SPI();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+ ms5611::prom_u &_prom;
+
+ /**
+ * Send a reset command to the MS5611.
+ *
+ * This is required after any bus reset.
+ */
+ int _reset();
+
+ /**
+ * Send a measure command to the MS5611.
+ *
+ * @param addr Which address to use for the measure operation.
+ */
+ int _measure(unsigned addr);
+
+ /**
+ * Read the MS5611 PROM
+ *
+ * @return OK if the PROM reads successfully.
+ */
+ int _read_prom();
+
+ /**
+ * Read a 16-bit register value.
+ *
+ * @param reg The register to read.
+ */
+ uint16_t _reg16(unsigned reg);
+
+ /**
+ * Wrapper around transfer() that prevents interrupt-context transfers
+ * from pre-empting us. The sensor may (does) share a bus with sensors
+ * that are polled from interrupt context (or we may be pre-empted)
+ * so we need to guarantee that transfers complete without interruption.
+ */
+ int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
+};
+
+device::Device *
+MS5611_spi_interface(ms5611::prom_u &prom_buf)
+{
+ return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+}
+
+MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
+ SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz */),
+ _prom(prom_buf)
+{
+}
+
+MS5611_SPI::~MS5611_SPI()
+{
+}
+
+int
+MS5611_SPI::init()
+{
+ int ret;
+
+ ret = SPI::init();
+ if (ret != OK) {
+ debug("SPI init failed");
+ goto out;
+ }
+
+ /* send reset command */
+ ret = _reset();
+ if (ret != OK) {
+ debug("reset failed");
+ goto out;
+ }
+
+ /* read PROM */
+ ret = _read_prom();
+ if (ret != OK) {
+ debug("prom readout failed");
+ goto out;
+ }
+
+out:
+ return ret;
+}
+
+int
+MS5611_SPI::read(unsigned offset, void *data, unsigned count)
+{
+ union _cvt {
+ uint8_t b[4];
+ uint32_t w;
+ } *cvt = (_cvt *)data;
+ uint8_t buf[4] = { 0 | DIR_WRITE, 0, 0, 0 };
+
+ /* read the most recent measurement */
+ int ret = _transfer(&buf[0], &buf[0], sizeof(buf));
+
+ if (ret == OK) {
+ /* fetch the raw value */
+ cvt->b[0] = buf[3];
+ cvt->b[1] = buf[2];
+ cvt->b[2] = buf[1];
+ cvt->b[3] = 0;
+
+ ret = count;
+ }
+
+ return ret;
+}
+
+int
+MS5611_SPI::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+ case IOCTL_RESET:
+ ret = _reset();
+ break;
+
+ case IOCTL_MEASURE:
+ ret = _measure(arg);
+ break;
+
+ default:
+ ret = EINVAL;
+ }
+
+ if (ret != OK) {
+ errno = ret;
+ return -1;
+ }
+ return 0;
+}
+
+int
+MS5611_SPI::_reset()
+{
+ uint8_t cmd = ADDR_RESET_CMD | DIR_WRITE;
+
+ return _transfer(&cmd, nullptr, 1);
+}
+
+int
+MS5611_SPI::_measure(unsigned addr)
+{
+ uint8_t cmd = addr | DIR_WRITE;
+
+ return _transfer(&cmd, nullptr, 1);
+}
+
+
+int
+MS5611_SPI::_read_prom()
+{
+ /*
+ * Wait for PROM contents to be in the device (2.8 ms) in the case we are
+ * called immediately after reset.
+ */
+ usleep(3000);
+
+ /* read and convert PROM words */
+ bool all_zero = true;
+ for (int i = 0; i < 8; i++) {
+ uint8_t cmd = (ADDR_PROM_SETUP + (i * 2));
+ _prom.c[i] = _reg16(cmd);
+ if (_prom.c[i] != 0)
+ all_zero = false;
+ //debug("prom[%u]=0x%x", (unsigned)i, (unsigned)_prom.c[i]);
+ }
+
+ /* calculate CRC and return success/failure accordingly */
+ int ret = ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
+ if (ret != OK) {
+ debug("crc failed");
+ }
+ if (all_zero) {
+ debug("prom all zero");
+ ret = -EIO;
+ }
+ return ret;
+}
+
+uint16_t
+MS5611_SPI::_reg16(unsigned reg)
+{
+ uint8_t cmd[3] = { (uint8_t)(reg | DIR_READ), 0, 0 };
+
+ _transfer(cmd, cmd, sizeof(cmd));
+
+ return (uint16_t)(cmd[1] << 8) | cmd[2];
+}
+
+int
+MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
+ return transfer(send, recv, len);
+}
+
+#endif /* PX4_SPIDEV_BARO */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 5147ac500..0fbd84924 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-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
@@ -34,7 +34,7 @@
/**
* @file fmu.cpp
*
- * Driver/configurator for the PX4 FMU multi-purpose port.
+ * Driver/configurator for the PX4 FMU multi-purpose port on v1 and v2 boards.
*/
#include <nuttx/config.h>
@@ -57,29 +57,41 @@
#include <drivers/device/device.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_gpio.h>
-#include <drivers/boards/px4fmu/px4fmu_internal.h>
#include <drivers/drv_hrt.h>
+#include <board_config.h>
+
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
#include <systemlib/mixer/mixer.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
+#include <systemlib/board_serial.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_rc_input.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_armed.h>
-#include <systemlib/err.h>
-#include <systemlib/ppm_decode.h>
+
+#ifdef HRT_PPM_CHANNEL
+# include <systemlib/ppm_decode.h>
+#endif
+
+/*
+ * This is the analog to FMU_INPUT_DROP_LIMIT_US on the IO side
+ */
+
+#define CONTROL_INPUT_DROP_LIMIT_MS 20
class PX4FMU : public device::CDev
{
public:
enum Mode {
+ MODE_NONE,
MODE_2PWM,
MODE_4PWM,
- MODE_NONE
+ MODE_6PWM,
};
PX4FMU();
virtual ~PX4FMU();
@@ -95,7 +107,12 @@ public:
int set_pwm_alt_channels(uint32_t channels);
private:
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
static const unsigned _max_actuators = 4;
+#endif
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ static const unsigned _max_actuators = 6;
+#endif
Mode _mode;
unsigned _pwm_default_rate;
@@ -104,19 +121,27 @@ private:
unsigned _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_armed;
orb_advert_t _t_outputs;
- orb_advert_t _t_actuators_effective;
unsigned _num_outputs;
bool _primary_pwm_device;
volatile bool _task_should_exit;
bool _armed;
+ bool _pwm_on;
MixerGroup *_mixers;
actuator_controls_s _controls;
+ pwm_limit_t _pwm_limit;
+ uint16_t _failsafe_pwm[_max_actuators];
+ uint16_t _disarmed_pwm[_max_actuators];
+ uint16_t _min_pwm[_max_actuators];
+ uint16_t _max_pwm[_max_actuators];
+ unsigned _num_failsafe_set;
+ unsigned _num_disarmed_set;
+
static void task_main_trampoline(int argc, char *argv[]);
void task_main() __attribute__((noreturn));
@@ -138,6 +163,7 @@ private:
static const unsigned _ngpio;
void gpio_reset(void);
+ void sensor_reset(int ms);
void gpio_set_function(uint32_t gpios, int function);
void gpio_write(uint32_t gpios, int function);
uint32_t gpio_read(void);
@@ -146,6 +172,7 @@ private:
};
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
@@ -154,6 +181,22 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
+#endif
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
+
+ {0, GPIO_VDD_5V_PERIPH_EN, 0},
+ {0, GPIO_VDD_3V3_SENSORS_EN, 0},
+ {GPIO_VDD_BRICK_VALID, 0, 0},
+ {GPIO_VDD_SERVO_VALID, 0, 0},
+ {GPIO_VDD_5V_HIPOWER_OC, 0, 0},
+ {GPIO_VDD_5V_PERIPH_OC, 0, 0},
+#endif
};
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
@@ -166,7 +209,7 @@ PX4FMU *g_fmu;
} // namespace
PX4FMU::PX4FMU() :
- CDev("fmuservo", "/dev/px4fmu"),
+ CDev("fmuservo", PX4FMU_DEVICE_PATH),
_mode(MODE_NONE),
_pwm_default_rate(50),
_pwm_alt_rate(50),
@@ -174,15 +217,24 @@ PX4FMU::PX4FMU() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_armed(-1),
_t_outputs(0),
- _t_actuators_effective(0),
_num_outputs(0),
_primary_pwm_device(false),
_task_should_exit(false),
_armed(false),
- _mixers(nullptr)
+ _pwm_on(false),
+ _mixers(nullptr),
+ _failsafe_pwm({0}),
+ _disarmed_pwm({0}),
+ _num_failsafe_set(0),
+ _num_disarmed_set(0)
{
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ _min_pwm[i] = PWM_DEFAULT_MIN;
+ _max_pwm[i] = PWM_DEFAULT_MAX;
+ }
+
_debug_enabled = true;
}
@@ -240,11 +292,11 @@ PX4FMU::init()
/* start the IO interface task */
_task = task_spawn_cmd("fmuservo",
- SCHED_DEFAULT,
- SCHED_PRIORITY_DEFAULT,
- 2048,
- (main_t)&PX4FMU::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT,
+ 2048,
+ (main_t)&PX4FMU::task_main_trampoline,
+ nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -271,17 +323,44 @@ PX4FMU::set_mode(Mode mode)
* are presented on the output pins.
*/
switch (mode) {
- case MODE_2PWM: // multi-port with flow control lines as PWM
- case MODE_4PWM: // multi-port as 4 PWM outs
- debug("MODE_%dPWM", (mode == MODE_2PWM) ? 2 : 4);
-
+ case MODE_2PWM: // v1 multi-port with flow control lines as PWM
+ debug("MODE_2PWM");
+
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0x3);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+
+ break;
+
+ case MODE_4PWM: // v1 multi-port as 4 PWM outs
+ debug("MODE_4PWM");
+
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0xf);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+
+ break;
+
+ case MODE_6PWM: // v2 PWMs as 6 PWM outs
+ debug("MODE_6PWM");
+
/* default output rates */
_pwm_default_rate = 50;
_pwm_alt_rate = 50;
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
- up_pwm_servo_init((mode == MODE_2PWM) ? 0x3 : 0xf);
+ up_pwm_servo_init(0x3f);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
break;
@@ -316,6 +395,7 @@ PX4FMU::set_pwm_rate(uint32_t rate_map, unsigned default_rate, unsigned alt_rate
// get the channel mask for this rate group
uint32_t mask = up_pwm_servo_get_rate_group(group);
+
if (mask == 0)
continue;
@@ -329,6 +409,7 @@ PX4FMU::set_pwm_rate(uint32_t rate_map, unsigned default_rate, unsigned alt_rate
// not a legal map, bail
return -EINVAL;
}
+
} else {
// set it - errors here are unexpected
if (alt != 0) {
@@ -336,6 +417,7 @@ PX4FMU::set_pwm_rate(uint32_t rate_map, unsigned default_rate, unsigned alt_rate
warn("rate group set alt failed");
return -EINVAL;
}
+
} else {
if (up_pwm_servo_set_rate_group_update(group, _pwm_default_rate) != OK) {
warn("rate group set default failed");
@@ -345,6 +427,7 @@ PX4FMU::set_pwm_rate(uint32_t rate_map, unsigned default_rate, unsigned alt_rate
}
}
}
+
_pwm_alt_rate_channels = rate_map;
_pwm_default_rate = default_rate;
_pwm_alt_rate = alt_rate;
@@ -376,8 +459,8 @@ PX4FMU::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -386,27 +469,23 @@ PX4FMU::task_main()
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
&outputs);
- /* advertise the effective control inputs */
- actuator_controls_effective_s controls_effective;
- memset(&controls_effective, 0, sizeof(controls_effective));
- /* advertise the effective control inputs */
- _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1),
- &controls_effective);
-
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_armed;
fds[1].events = POLLIN;
- unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4;
-
+#ifdef HRT_PPM_CHANNEL
// rc input, published to ORB
struct rc_input_values rc_in;
orb_advert_t to_input_rc = 0;
memset(&rc_in, 0, sizeof(rc_in));
rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM;
+#endif
+
+ /* initialize PWM limit lib */
+ pwm_limit_init(&_pwm_limit);
log("starting");
@@ -420,6 +499,7 @@ PX4FMU::task_main()
* We always mix at max rate; some channels may update slower.
*/
unsigned max_rate = (_pwm_default_rate > _pwm_alt_rate) ? _pwm_default_rate : _pwm_alt_rate;
+
if (_current_update_rate != max_rate) {
_current_update_rate = max_rate;
int update_rate_in_ms = int(1000 / _current_update_rate);
@@ -428,6 +508,7 @@ PX4FMU::task_main()
if (update_rate_in_ms < 2) {
update_rate_in_ms = 2;
}
+
/* reject slower than 10 Hz updates */
if (update_rate_in_ms > 100) {
update_rate_in_ms = 100;
@@ -442,100 +523,146 @@ PX4FMU::task_main()
/* sleep waiting for data, stopping to check for PPM
* input at 100Hz */
- int ret = ::poll(&fds[0], 2, 10);
+ int ret = ::poll(&fds[0], 2, CONTROL_INPUT_DROP_LIMIT_MS);
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
usleep(1000000);
continue;
- }
- /* do we have a control update? */
- if (fds[0].revents & POLLIN) {
-
- /* get controls - must always do this to avoid spinning */
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
-
- /* can we mix? */
- if (_mixers != nullptr) {
-
- /* do mixing */
- outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
- outputs.timestamp = hrt_absolute_time();
-
- // XXX output actual limited values
- memcpy(&controls_effective, &_controls, sizeof(controls_effective));
-
- orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective);
-
- /* iterate actuators */
- for (unsigned i = 0; i < num_outputs; i++) {
-
- /* last resort: catch NaN, INF and out-of-band errors */
- if (i < outputs.noutputs &&
- isfinite(outputs.output[i]) &&
- outputs.output[i] >= -1.0f &&
- outputs.output[i] <= 1.0f) {
- /* scale for PWM output 900 - 2100us */
- outputs.output[i] = 1500 + (600 * outputs.output[i]);
- } else {
- /*
- * Value is NaN, INF or out of band - set to the minimum value.
- * This will be clearly visible on the servo status and will limit the risk of accidentally
- * spinning motors. It would be deadly in flight.
- */
- outputs.output[i] = 900;
+ } else if (ret == 0) {
+ /* timeout: no control data, switch to failsafe values */
+// warnx("no PWM: failsafe");
+
+ } else {
+
+ /* do we have a control update? */
+ if (fds[0].revents & POLLIN) {
+
+ /* get controls - must always do this to avoid spinning */
+ orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls);
+
+ /* can we mix? */
+ if (_mixers != nullptr) {
+
+ unsigned num_outputs;
+
+ switch (_mode) {
+ case MODE_2PWM:
+ num_outputs = 2;
+ break;
+
+ case MODE_4PWM:
+ num_outputs = 4;
+ break;
+
+ case MODE_6PWM:
+ num_outputs = 6;
+ break;
+
+ default:
+ num_outputs = 0;
+ break;
}
- /* output to the servo */
- up_pwm_servo_set(i, outputs.output[i]);
- }
+ /* do mixing */
+ outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
+ outputs.timestamp = hrt_absolute_time();
+
+ /* iterate actuators */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ /* last resort: catch NaN, INF and out-of-band errors */
+ if (i >= outputs.noutputs ||
+ !isfinite(outputs.output[i]) ||
+ outputs.output[i] < -1.0f ||
+ outputs.output[i] > 1.0f) {
+ /*
+ * Value is NaN, INF or out of band - set to the minimum value.
+ * This will be clearly visible on the servo status and will limit the risk of accidentally
+ * spinning motors. It would be deadly in flight.
+ */
+ outputs.output[i] = -1.0f;
+ }
+ }
- /* and publish for anyone that cares to see */
- orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs);
+ uint16_t pwm_limited[num_outputs];
+
+ pwm_limit_calc(_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
+
+ /* output to the servos */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ up_pwm_servo_set(i, pwm_limited[i]);
+ }
+
+ /* and publish for anyone that cares to see */
+ orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs);
+ }
}
- }
- /* how about an arming update? */
- if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ /* how about an arming update? */
+ if (fds[1].revents & POLLIN) {
+ actuator_armed_s aa;
+
+ /* get new value */
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
+
+ /* update the armed status and check that we're not locked down */
+ bool set_armed = aa.armed && !aa.lockdown;
- /* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ if (_armed != set_armed)
+ _armed = set_armed;
- /* update PWM servo armed status if armed and not locked down */
- bool set_armed = aa.armed && !aa.lockdown;
- if (set_armed != _armed) {
- _armed = set_armed;
- up_pwm_servo_arm(set_armed);
+ /* update PWM status if armed or if disarmed PWM values are set */
+ bool pwm_on = (aa.armed || _num_disarmed_set > 0);
+
+ if (_pwm_on != pwm_on) {
+ _pwm_on = pwm_on;
+ up_pwm_servo_arm(pwm_on);
+ }
}
}
+#ifdef HRT_PPM_CHANNEL
+
// see if we have new PPM input data
- if (ppm_last_valid_decode != rc_in.timestamp) {
+ if (ppm_last_valid_decode != rc_in.timestamp_last_signal) {
// we have a new PPM frame. Publish it.
rc_in.channel_count = ppm_decoded_channels;
+
if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) {
rc_in.channel_count = RC_INPUT_MAX_CHANNELS;
}
- for (uint8_t i=0; i<rc_in.channel_count; i++) {
+
+ for (uint8_t i = 0; i < rc_in.channel_count; i++) {
rc_in.values[i] = ppm_buffer[i];
}
- rc_in.timestamp = ppm_last_valid_decode;
+
+ rc_in.timestamp_publication = ppm_last_valid_decode;
+ rc_in.timestamp_last_signal = ppm_last_valid_decode;
+
+ rc_in.rc_ppm_frame_length = ppm_frame_length;
+ rc_in.rssi = RC_INPUT_RSSI_MAX;
+ rc_in.rc_failsafe = false;
+ rc_in.rc_lost = false;
+ rc_in.rc_lost_frame_count = 0;
+ rc_in.rc_total_frame_count = 0;
/* lazily advertise on first publication */
if (to_input_rc == 0) {
to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_in);
- } else {
+
+ } else {
orb_publish(ORB_ID(input_rc), to_input_rc, &rc_in);
}
}
+
+#endif
+
}
::close(_t_actuators);
- ::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_armed);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -579,6 +706,7 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
switch (_mode) {
case MODE_2PWM:
case MODE_4PWM:
+ case MODE_6PWM:
ret = pwm_ioctl(filp, cmd, arg);
break;
@@ -615,42 +743,243 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
up_pwm_servo_arm(false);
break;
+ case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_default_rate;
+ break;
+
case PWM_SERVO_SET_UPDATE_RATE:
ret = set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_GET_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_alt_rate;
+ break;
+
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
ret = set_pwm_rate(arg, _pwm_default_rate, _pwm_alt_rate);
break;
- case PWM_SERVO_SET(2):
+ case PWM_SERVO_GET_SELECT_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_alt_rate_channels;
+ break;
+
+ case PWM_SERVO_SET_FAILSAFE_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] > PWM_HIGHEST_MAX) {
+ _failsafe_pwm[i] = PWM_HIGHEST_MAX;
+
+ } else if (pwm->values[i] < PWM_LOWEST_MIN) {
+ _failsafe_pwm[i] = PWM_LOWEST_MIN;
+
+ } else {
+ _failsafe_pwm[i] = pwm->values[i];
+ }
+ }
+
+ /*
+ * update the counter
+ * this is needed to decide if disarmed PWM output should be turned on or not
+ */
+ _num_failsafe_set = 0;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ if (_failsafe_pwm[i] > 0)
+ _num_failsafe_set++;
+ }
+
+ break;
+ }
+
+ case PWM_SERVO_GET_FAILSAFE_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _failsafe_pwm[i];
+ }
+
+ pwm->channel_count = _max_actuators;
+ break;
+ }
+
+ case PWM_SERVO_SET_DISARMED_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] > PWM_HIGHEST_MAX) {
+ _disarmed_pwm[i] = PWM_HIGHEST_MAX;
+
+ } else if (pwm->values[i] < PWM_LOWEST_MIN) {
+ _disarmed_pwm[i] = PWM_LOWEST_MIN;
+
+ } else {
+ _disarmed_pwm[i] = pwm->values[i];
+ }
+ }
+
+ /*
+ * update the counter
+ * this is needed to decide if disarmed PWM output should be turned on or not
+ */
+ _num_disarmed_set = 0;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ if (_disarmed_pwm[i] > 0)
+ _num_disarmed_set++;
+ }
+
+ break;
+ }
+
+ case PWM_SERVO_GET_DISARMED_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _disarmed_pwm[i];
+ }
+
+ pwm->channel_count = _max_actuators;
+ break;
+ }
+
+ case PWM_SERVO_SET_MIN_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] > PWM_HIGHEST_MIN) {
+ _min_pwm[i] = PWM_HIGHEST_MIN;
+
+ } else if (pwm->values[i] < PWM_LOWEST_MIN) {
+ _min_pwm[i] = PWM_LOWEST_MIN;
+
+ } else {
+ _min_pwm[i] = pwm->values[i];
+ }
+ }
+
+ break;
+ }
+
+ case PWM_SERVO_GET_MIN_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _min_pwm[i];
+ }
+
+ pwm->channel_count = _max_actuators;
+ arg = (unsigned long)&pwm;
+ break;
+ }
+
+ case PWM_SERVO_SET_MAX_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] < PWM_LOWEST_MAX) {
+ _max_pwm[i] = PWM_LOWEST_MAX;
+
+ } else if (pwm->values[i] > PWM_HIGHEST_MAX) {
+ _max_pwm[i] = PWM_HIGHEST_MAX;
+
+ } else {
+ _max_pwm[i] = pwm->values[i];
+ }
+ }
+
+ break;
+ }
+
+ case PWM_SERVO_GET_MAX_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values *)arg;
+
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _max_pwm[i];
+ }
+
+ pwm->channel_count = _max_actuators;
+ arg = (unsigned long)&pwm;
+ break;
+ }
+
+ case PWM_SERVO_SET(5):
+ case PWM_SERVO_SET(4):
+ if (_mode < MODE_6PWM) {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* FALLTHROUGH */
case PWM_SERVO_SET(3):
- if (_mode != MODE_4PWM) {
+ case PWM_SERVO_SET(2):
+ if (_mode < MODE_4PWM) {
ret = -EINVAL;
break;
}
- /* FALLTHROUGH */
- case PWM_SERVO_SET(0):
+ /* FALLTHROUGH */
case PWM_SERVO_SET(1):
- if (arg < 2100) {
+ case PWM_SERVO_SET(0):
+ if (arg <= 2100) {
up_pwm_servo_set(cmd - PWM_SERVO_SET(0), arg);
+
} else {
ret = -EINVAL;
}
break;
- case PWM_SERVO_GET(2):
+ case PWM_SERVO_GET(5):
+ case PWM_SERVO_GET(4):
+ if (_mode < MODE_6PWM) {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* FALLTHROUGH */
case PWM_SERVO_GET(3):
- if (_mode != MODE_4PWM) {
+ case PWM_SERVO_GET(2):
+ if (_mode < MODE_4PWM) {
ret = -EINVAL;
break;
}
- /* FALLTHROUGH */
- case PWM_SERVO_GET(0):
+ /* FALLTHROUGH */
case PWM_SERVO_GET(1):
+ case PWM_SERVO_GET(0):
*(servo_position_t *)arg = up_pwm_servo_get(cmd - PWM_SERVO_GET(0));
break;
@@ -658,20 +987,67 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET_RATEGROUP(1):
case PWM_SERVO_GET_RATEGROUP(2):
case PWM_SERVO_GET_RATEGROUP(3):
+ case PWM_SERVO_GET_RATEGROUP(4):
+ case PWM_SERVO_GET_RATEGROUP(5):
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
break;
- case PWM_SERVO_GET_COUNT:
+ case PWM_SERVO_GET_COUNT:
case MIXERIOCGETOUTPUTCOUNT:
- if (_mode == MODE_4PWM) {
+ switch (_mode) {
+ case MODE_6PWM:
+ *(unsigned *)arg = 6;
+ break;
+
+ case MODE_4PWM:
*(unsigned *)arg = 4;
+ break;
- } else {
+ case MODE_2PWM:
*(unsigned *)arg = 2;
+ break;
+
+ default:
+ ret = -EINVAL;
+ break;
}
break;
+ case PWM_SERVO_SET_COUNT: {
+ /* change the number of outputs that are enabled for
+ * PWM. This is used to change the split between GPIO
+ * and PWM under control of the flight config
+ * parameters. Note that this does not allow for
+ * changing a set of pins to be used for serial on
+ * FMUv1
+ */
+ switch (arg) {
+ case 0:
+ set_mode(MODE_NONE);
+ break;
+
+ case 2:
+ set_mode(MODE_2PWM);
+ break;
+
+ case 4:
+ set_mode(MODE_4PWM);
+ break;
+
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ case 6:
+ set_mode(MODE_6PWM);
+ break;
+#endif
+
+ default:
+ ret = -EINVAL;
+ break;
+ }
+ break;
+ }
+
case MIXERIOCRESET:
if (_mixers != nullptr) {
delete _mixers;
@@ -722,6 +1098,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = -EINVAL;
}
}
+
break;
}
@@ -743,39 +1120,132 @@ ssize_t
PX4FMU::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
- uint16_t values[4];
+ uint16_t values[6];
- if (count > 4) {
- // we only have 4 PWM outputs on the FMU
- count = 4;
+ if (count > 6) {
+ // we have at most 6 outputs
+ count = 6;
}
// allow for misaligned values
- memcpy(values, buffer, count*2);
+ memcpy(values, buffer, count * 2);
- for (uint8_t i=0; i<count; i++) {
+ for (uint8_t i = 0; i < count; i++) {
up_pwm_servo_set(i, values[i]);
}
+
return count * 2;
}
void
+PX4FMU::sensor_reset(int ms)
+{
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+
+ if (ms < 1) {
+ ms = 1;
+ }
+
+ /* disable SPI bus */
+ stm32_configgpio(GPIO_SPI_CS_GYRO_OFF);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF);
+ stm32_configgpio(GPIO_SPI_CS_BARO_OFF);
+ stm32_configgpio(GPIO_SPI_CS_MPU_OFF);
+
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0);
+
+ stm32_configgpio(GPIO_SPI1_SCK_OFF);
+ stm32_configgpio(GPIO_SPI1_MISO_OFF);
+ stm32_configgpio(GPIO_SPI1_MOSI_OFF);
+
+ stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
+ stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
+ stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
+
+ stm32_configgpio(GPIO_GYRO_DRDY_OFF);
+ stm32_configgpio(GPIO_MAG_DRDY_OFF);
+ stm32_configgpio(GPIO_ACCEL_DRDY_OFF);
+ stm32_configgpio(GPIO_EXTI_MPU_DRDY_OFF);
+
+ stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0);
+ stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0);
+ stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0);
+ stm32_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0);
+
+ /* set the sensor rail off */
+ stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
+ stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
+
+ /* wait for the sensor rail to reach GND */
+ usleep(ms * 1000);
+ warnx("reset done, %d ms", ms);
+
+ /* re-enable power */
+
+ /* switch the sensor rail back on */
+ stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
+
+ /* wait a bit before starting SPI, different times didn't influence results */
+ usleep(100);
+
+ /* reconfigure the SPI pins */
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+ stm32_configgpio(GPIO_SPI_CS_MPU);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+
+ // // XXX bring up the EXTI pins again
+ // stm32_configgpio(GPIO_GYRO_DRDY);
+ // stm32_configgpio(GPIO_MAG_DRDY);
+ // stm32_configgpio(GPIO_ACCEL_DRDY);
+ // stm32_configgpio(GPIO_EXTI_MPU_DRDY);
+
+#endif
+#endif
+}
+
+
+void
PX4FMU::gpio_reset(void)
{
/*
- * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
- * to input mode.
+ * Setup default GPIO config - all pins as GPIOs, input if
+ * possible otherwise output if possible.
*/
- for (unsigned i = 0; i < _ngpio; i++)
- stm32_configgpio(_gpio_tab[i].input);
+ for (unsigned i = 0; i < _ngpio; i++) {
+ if (_gpio_tab[i].input != 0) {
+ stm32_configgpio(_gpio_tab[i].input);
+
+ } else if (_gpio_tab[i].output != 0) {
+ stm32_configgpio(_gpio_tab[i].output);
+ }
+ }
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ /* if we have a GPIO direction control, set it to zero (input) */
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
stm32_configgpio(GPIO_GPIO_DIR);
+#endif
}
void
PX4FMU::gpio_set_function(uint32_t gpios, int function)
{
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+
/*
* GPIOs 0 and 1 must have the same direction as they are buffered
* by a shared 2-port driver. Any attempt to set either sets both.
@@ -788,6 +1258,8 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
stm32_gpiowrite(GPIO_GPIO_DIR, 1);
}
+#endif
+
/* configure selected GPIOs as required */
for (unsigned i = 0; i < _ngpio; i++) {
if (gpios & (1 << i)) {
@@ -809,9 +1281,13 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
}
}
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+
/* flip buffer to input mode if required */
if ((GPIO_SET_INPUT == function) && (gpios & 3))
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+
+#endif
}
void
@@ -849,6 +1325,10 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
gpio_reset();
break;
+ case GPIO_SENSOR_RAIL_RESET:
+ sensor_reset(arg);
+ break;
+
case GPIO_SET_OUTPUT:
case GPIO_SET_INPUT:
case GPIO_SET_ALT_1:
@@ -912,14 +1392,22 @@ fmu_new_mode(PortMode new_mode)
/* nothing more to do here */
break;
- case PORT_FULL_SERIAL:
- /* set all multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
case PORT_FULL_PWM:
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
/* select 4-pin PWM mode */
servo_mode = PX4FMU::MODE_4PWM;
+#endif
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ servo_mode = PX4FMU::MODE_6PWM;
+#endif
+ break;
+
+ /* mixed modes supported on v1 board only */
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+
+ case PORT_FULL_SERIAL:
+ /* set all multi-GPIOs to serial mode */
+ gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
break;
case PORT_GPIO_AND_SERIAL:
@@ -938,6 +1426,10 @@ fmu_new_mode(PortMode new_mode)
/* select 2-pin PWM mode */
servo_mode = PX4FMU::MODE_2PWM;
break;
+#endif
+
+ default:
+ return -1;
}
/* adjust GPIO config for serial mode(s) */
@@ -975,25 +1467,128 @@ fmu_start(void)
return ret;
}
+int
+fmu_stop(void)
+{
+ int ret = OK;
+
+ if (g_fmu != nullptr) {
+
+ delete g_fmu;
+ g_fmu = nullptr;
+ }
+
+ return ret;
+}
+
+void
+sensor_reset(int ms)
+{
+ int fd;
+
+ fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
+
+ if (fd < 0)
+ errx(1, "open fail");
+
+ if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0)
+ err(1, "servo arm failed");
+
+}
+
void
test(void)
{
- int fd;
+ int fd;
+ unsigned servo_count = 0;
+ unsigned pwm_value = 1000;
+ int direction = 1;
+ int ret;
- fd = open(PWM_OUTPUT_DEVICE_PATH, 0);
+ fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
if (fd < 0)
errx(1, "open fail");
if (ioctl(fd, PWM_SERVO_ARM, 0) < 0) err(1, "servo arm failed");
- if (ioctl(fd, PWM_SERVO_SET(0), 1000) < 0) err(1, "servo 1 set failed");
+ if (ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count) != 0) {
+ err(1, "Unable to get servo count\n");
+ }
+
+ warnx("Testing %u servos", (unsigned)servo_count);
+
+ struct pollfd fds;
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
+ for (;;) {
+ /* sweep all servos between 1000..2000 */
+ servo_position_t servos[servo_count];
+
+ for (unsigned i = 0; i < servo_count; i++)
+ servos[i] = pwm_value;
+
+ if (direction == 1) {
+ // use ioctl interface for one direction
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (ioctl(fd, PWM_SERVO_SET(i), servos[i]) < 0) {
+ err(1, "servo %u set failed", i);
+ }
+ }
+
+ } else {
+ // and use write interface for the other direction
+ ret = write(fd, servos, sizeof(servos));
+
+ if (ret != (int)sizeof(servos))
+ err(1, "error writing PWM servo data, wrote %u got %d", sizeof(servos), ret);
+ }
+
+ if (direction > 0) {
+ if (pwm_value < 2000) {
+ pwm_value++;
+
+ } else {
+ direction = -1;
+ }
+
+ } else {
+ if (pwm_value > 1000) {
+ pwm_value--;
+
+ } else {
+ direction = 1;
+ }
+ }
+
+ /* readback servo values */
+ for (unsigned i = 0; i < servo_count; i++) {
+ servo_position_t value;
+
+ if (ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&value))
+ err(1, "error reading PWM servo %d", i);
+
+ if (value != servos[i])
+ errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
+ }
+
+ /* Check if user wants to quit */
+ char c;
+ ret = poll(&fds, 1, 0);
- if (ioctl(fd, PWM_SERVO_SET(1), 1200) < 0) err(1, "servo 2 set failed");
+ if (ret > 0) {
- if (ioctl(fd, PWM_SERVO_SET(2), 1400) < 0) err(1, "servo 3 set failed");
+ read(0, &c, 1);
- if (ioctl(fd, PWM_SERVO_SET(3), 1600) < 0) err(1, "servo 4 set failed");
+ if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("User abort\n");
+ break;
+ }
+ }
+ }
close(fd);
@@ -1044,6 +1639,21 @@ fmu_main(int argc, char *argv[])
PortMode new_mode = PORT_MODE_UNSET;
const char *verb = argv[1];
+ if (!strcmp(verb, "stop")) {
+ fmu_stop();
+ errx(0, "FMU driver stopped");
+ }
+
+ if (!strcmp(verb, "id")) {
+ char id[12];
+ (void)get_board_serial(id);
+
+ errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
+ (unsigned)id[0], (unsigned)id[1], (unsigned)id[2], (unsigned)id[3], (unsigned)id[4], (unsigned)id[5],
+ (unsigned)id[6], (unsigned)id[7], (unsigned)id[8], (unsigned)id[9], (unsigned)id[10], (unsigned)id[11]);
+ }
+
+
if (fmu_start() != OK)
errx(1, "failed to start the FMU driver");
@@ -1053,12 +1663,14 @@ fmu_main(int argc, char *argv[])
if (!strcmp(verb, "mode_gpio")) {
new_mode = PORT_FULL_GPIO;
- } else if (!strcmp(verb, "mode_serial")) {
- new_mode = PORT_FULL_SERIAL;
-
} else if (!strcmp(verb, "mode_pwm")) {
new_mode = PORT_FULL_PWM;
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+
+ } else if (!strcmp(verb, "mode_serial")) {
+ new_mode = PORT_FULL_SERIAL;
+
} else if (!strcmp(verb, "mode_gpio_serial")) {
new_mode = PORT_GPIO_AND_SERIAL;
@@ -1067,6 +1679,7 @@ fmu_main(int argc, char *argv[])
} else if (!strcmp(verb, "mode_pwm_gpio")) {
new_mode = PORT_PWM_AND_GPIO;
+#endif
}
/* was a new mode set? */
@@ -1087,7 +1700,25 @@ fmu_main(int argc, char *argv[])
if (!strcmp(verb, "fake"))
fake(argc - 1, argv + 1);
+ if (!strcmp(verb, "sensor_reset")) {
+ if (argc > 2) {
+ int reset_time = strtol(argv[2], 0, 0);
+ sensor_reset(reset_time);
+
+ } else {
+ sensor_reset(0);
+ warnx("resettet default time");
+ }
+
+ exit(0);
+ }
+
+
fprintf(stderr, "FMU: unrecognised command, try:\n");
- fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio\n");
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
+#endif
exit(1);
}
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index 328e5a684..2054faa12 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -38,4 +38,9 @@
MODULE_COMMAND = px4io
SRCS = px4io.cpp \
- uploader.cpp
+ px4io_uploader.cpp \
+ px4io_serial.cpp \
+ px4io_i2c.cpp
+
+# XXX prune to just get UART registers
+INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 8b2fae12b..7c7b3dcb7 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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
@@ -35,7 +35,7 @@
* @file px4io.cpp
* Driver for the PX4IO board.
*
- * PX4IO is connected via I2C.
+ * PX4IO is connected via I2C or DMA enabled high-speed UART.
*/
#include <nuttx/config.h>
@@ -54,13 +54,14 @@
#include <unistd.h>
#include <fcntl.h>
#include <math.h>
+#include <crc32.h>
#include <arch/board/board.h>
#include <drivers/device/device.h>
-#include <drivers/device/i2c.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
+#include <drivers/drv_sbus.h>
#include <drivers/drv_gpio.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
@@ -73,96 +74,217 @@
#include <systemlib/param/param.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/battery_status.h>
+#include <uORB/topics/servorail_status.h>
#include <uORB/topics/parameter_update.h>
+
#include <debug.h>
#include <mavlink/mavlink_log.h>
-#include "uploader.h"
#include <modules/px4iofirmware/protocol.h>
+#include "uploader.h"
+
+extern device::Device *PX4IO_i2c_interface() weak_function;
+extern device::Device *PX4IO_serial_interface() weak_function;
+
#define PX4IO_SET_DEBUG _IOC(0xff00, 0)
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1)
+#define PX4IO_REBOOT_BOOTLOADER _IOC(0xff00, 2)
+#define PX4IO_CHECK_CRC _IOC(0xff00, 3)
+
+#define UPDATE_INTERVAL_MIN 2 // 2 ms -> 500 Hz
+#define ORB_CHECK_INTERVAL 200000 // 200 ms -> 5 Hz
+#define IO_POLL_INTERVAL 20000 // 20 ms -> 50 Hz
-class PX4IO : public device::I2C
+/**
+ * The PX4IO class.
+ *
+ * Encapsulates PX4FMU to PX4IO communications modeled as file operations.
+ */
+class PX4IO : public device::CDev
{
public:
- PX4IO();
+ /**
+ * Constructor.
+ *
+ * Initialize all class variables.
+ */
+ PX4IO(device::Device *interface);
+
+ /**
+ * Destructor.
+ *
+ * Wait for worker thread to terminate.
+ */
virtual ~PX4IO();
+ /**
+ * Initialize the PX4IO class.
+ *
+ * Retrieve relevant initial system parameters. Initialize PX4IO registers.
+ */
virtual int init();
+ /**
+ * Detect if a PX4IO is connected.
+ *
+ * Only validate if there is a PX4IO to talk to.
+ */
+ virtual int detect();
+
+ /**
+ * IO Control handler.
+ *
+ * Handle all IOCTL calls to the PX4IO file descriptor.
+ *
+ * @param[in] filp file handle (not used). This function is always called directly through object reference
+ * @param[in] cmd the IOCTL command
+ * @param[in] the IOCTL command parameter (optional)
+ */
virtual int ioctl(file *filp, int cmd, unsigned long arg);
+
+ /**
+ * write handler.
+ *
+ * Handle writes to the PX4IO file descriptor.
+ *
+ * @param[in] filp file handle (not used). This function is always called directly through object reference
+ * @param[in] buffer pointer to the data buffer to be written
+ * @param[in] len size in bytes to be written
+ * @return number of bytes written
+ */
virtual ssize_t write(file *filp, const char *buffer, size_t len);
/**
* Set the update rate for actuator outputs from FMU to IO.
*
- * @param rate The rate in Hz actuator outpus are sent to IO.
- * Min 10 Hz, max 400 Hz
+ * @param[in] rate The rate in Hz actuator outpus are sent to IO.
+ * Min 10 Hz, max 400 Hz
*/
- int set_update_rate(int rate);
+ int set_update_rate(int rate);
/**
* Set the battery current scaling and bias
*
- * @param amp_per_volt
- * @param amp_bias
+ * @param[in] amp_per_volt
+ * @param[in] amp_bias
*/
- void set_battery_current_scaling(float amp_per_volt, float amp_bias);
+ void set_battery_current_scaling(float amp_per_volt, float amp_bias);
/**
- * Print the current status of IO
- */
+ * Push failsafe values to IO.
+ *
+ * @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
+ * @param[in] len Number of channels, could up to 8
+ */
+ int set_failsafe_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Disable RC input handling
+ */
+ int disable_rc_handling();
+
+ /**
+ * Print IO status.
+ *
+ * Print all relevant IO status information
+ */
void print_status();
+ /**
+ * Fetch and print debug console output.
+ */
+ int print_debug();
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ /**
+ * Set the DSM VCC is controlled by relay one flag
+ *
+ * @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
+ */
+ inline void set_dsm_vcc_ctl(bool enable) {
+ _dsm_vcc_ctl = enable;
+ };
+
+ /**
+ * Get the DSM VCC is controlled by relay one flag
+ *
+ * @return true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
+ */
+ inline bool get_dsm_vcc_ctl() {
+ return _dsm_vcc_ctl;
+ };
+#endif
+
+ inline uint16_t system_status() const {return _status;}
+
private:
+ device::Device *_interface;
+
// XXX
- unsigned _max_actuators;
- unsigned _max_controls;
- unsigned _max_rc_input;
- unsigned _max_relays;
- unsigned _max_transfer;
+ unsigned _hardware; ///< Hardware revision
+ unsigned _max_actuators; ///< Maximum # of actuators supported by PX4IO
+ unsigned _max_controls; ///< Maximum # of controls supported by PX4IO
+ unsigned _max_rc_input; ///< Maximum receiver channels supported by PX4IO
+ unsigned _max_relays; ///< Maximum relays supported by PX4IO
+ unsigned _max_transfer; ///< Maximum number of I2C transfers supported by PX4IO
- unsigned _update_interval; ///< subscription interval limiting send rate
+ unsigned _update_interval; ///< Subscription interval limiting send rate
+ bool _rc_handling_disabled; ///< If set, IO does not evaluate, but only forward the RC values
+ unsigned _rc_chan_count; ///< Internal copy of the last seen number of RC channels
+ uint64_t _rc_last_valid; ///< last valid timestamp
- volatile int _task; ///< worker task
- volatile bool _task_should_exit;
+ volatile int _task; ///< worker task id
+ volatile bool _task_should_exit; ///< worker terminate flag
- int _mavlink_fd;
+ int _mavlink_fd; ///< mavlink file descriptor.
- perf_counter_t _perf_update;
+ perf_counter_t _perf_update; ///<local performance counter for status updates
+ perf_counter_t _perf_write; ///<local performance counter for PWM control writes
+ perf_counter_t _perf_chan_count; ///<local performance counter for channel number changes
/* cached IO state */
- uint16_t _status;
- uint16_t _alarms;
+ uint16_t _status; ///< Various IO status flags
+ uint16_t _alarms; ///< Various IO alarms
/* subscribed topics */
- int _t_actuators; ///< actuator controls topic
- int _t_armed; ///< system armed control topic
- int _t_vstatus; ///< system / vehicle status
- int _t_param; ///< parameter update topic
+ int _t_actuator_controls_0; ///< actuator controls group 0 topic
+ int _t_actuator_controls_1; ///< actuator controls group 1 topic
+ int _t_actuator_controls_2; ///< actuator controls group 2 topic
+ int _t_actuator_controls_3; ///< actuator controls group 3 topic
+ int _t_actuator_armed; ///< system armed control topic
+ int _t_vehicle_control_mode;///< vehicle control mode topic
+ int _t_param; ///< parameter update topic
+ int _t_vehicle_command; ///< vehicle command topic
/* advertised topics */
- orb_advert_t _to_input_rc; ///< rc inputs from io
- orb_advert_t _to_actuators_effective; ///< effective actuator controls topic
- orb_advert_t _to_outputs; ///< mixed servo outputs topic
- orb_advert_t _to_battery; ///< battery status / voltage
+ orb_advert_t _to_input_rc; ///< rc inputs from io
+ orb_advert_t _to_outputs; ///< mixed servo outputs topic
+ orb_advert_t _to_battery; ///< battery status / voltage
+ orb_advert_t _to_servorail; ///< servorail status
+ orb_advert_t _to_safety; ///< status of safety
- actuator_outputs_s _outputs; ///< mixed outputs
- actuator_controls_effective_s _controls_effective; ///< effective controls
+ actuator_outputs_s _outputs; ///< mixed outputs
+ servorail_status_s _servorail_status; ///< servorail status
bool _primary_pwm_device; ///< true if we are the default PWM output
+ bool _lockdown_override; ///< allow to override the safety lockdown
+
+ float _battery_amp_per_volt; ///< current sensor amps/volt
+ float _battery_amp_bias; ///< current sensor bias
+ float _battery_mamphour_total;///< amp hours consumed so far
+ uint64_t _battery_last_timestamp;///< last amp hour calculation timestamp
- float _battery_amp_per_volt;
- float _battery_amp_bias;
- float _battery_mamphour_total;
- uint64_t _battery_last_timestamp;
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ bool _dsm_vcc_ctl; ///< true if relay 1 controls DSM satellite RX power
+#endif
/**
* Trampoline to the worker task
@@ -175,9 +297,14 @@ private:
void task_main();
/**
- * Send controls to IO
+ * Send controls for one group to IO
+ */
+ int io_set_control_state(unsigned group);
+
+ /**
+ * Send all controls to IO
*/
- int io_set_control_state();
+ int io_set_control_groups();
/**
* Update IO's arming-related state
@@ -197,6 +324,11 @@ private:
int io_get_status();
/**
+ * Disable RC input handling
+ */
+ int io_disable_rc_handling();
+
+ /**
* Fetch RC inputs from IO.
*
* @param input_rc Input structure to populate.
@@ -210,11 +342,6 @@ private:
int io_publish_raw_rc();
/**
- * Fetch and publish the mixed control values.
- */
- int io_publish_mixed_controls();
-
- /**
* Fetch and publish the PWM servo outputs.
*/
int io_publish_pwm_outputs();
@@ -226,7 +353,7 @@ private:
* @param offset Register offset to start writing at.
* @param values Pointer to array of values to write.
* @param num_values The number of values to write.
- * @return Zero if all values were successfully written.
+ * @return OK if all values were successfully written.
*/
int io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
@@ -236,7 +363,7 @@ private:
* @param page Register page to write to.
* @param offset Register offset to write to.
* @param value Value to write.
- * @return Zero if the value was written successfully.
+ * @return OK if the value was written successfully.
*/
int io_reg_set(uint8_t page, uint8_t offset, const uint16_t value);
@@ -247,7 +374,7 @@ private:
* @param offset Register offset to start reading from.
* @param values Pointer to array where values should be stored.
* @param num_values The number of values to read.
- * @return Zero if all values were successfully read.
+ * @return OK if all values were successfully read.
*/
int io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_values);
@@ -274,7 +401,7 @@ private:
/**
* Send mixer definition text to IO
*/
- int mixer_send(const char *buf, unsigned buflen);
+ int mixer_send(const char *buf, unsigned buflen, unsigned retries = 3);
/**
* Handle a status update from IO.
@@ -294,51 +421,92 @@ private:
*/
int io_handle_alarms(uint16_t alarms);
-};
+ /**
+ * Handle issuing dsm bind ioctl to px4io.
+ *
+ * @param dsmMode 0:dsm2, 1:dsmx
+ */
+ void dsm_bind_ioctl(int dsmMode);
+
+ /**
+ * Handle a battery update from IO.
+ *
+ * Publish IO battery information if necessary.
+ *
+ * @param vbatt vbatt register
+ * @param ibatt ibatt register
+ */
+ void io_handle_battery(uint16_t vbatt, uint16_t ibatt);
+
+ /**
+ * Handle a servorail update from IO.
+ *
+ * Publish servo rail information if necessary.
+ *
+ * @param vservo vservo register
+ * @param vrssi vrssi register
+ */
+ void io_handle_vservo(uint16_t vservo, uint16_t vrssi);
+};
namespace
{
-PX4IO *g_dev;
+PX4IO *g_dev = nullptr;
}
-PX4IO::PX4IO() :
- I2C("px4io", "/dev/px4io", PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO, 320000),
+PX4IO::PX4IO(device::Device *interface) :
+ CDev("px4io", PX4IO_DEVICE_PATH),
+ _interface(interface),
+ _hardware(0),
_max_actuators(0),
_max_controls(0),
_max_rc_input(0),
_max_relays(0),
_max_transfer(16), /* sensible default */
_update_interval(0),
+ _rc_handling_disabled(false),
+ _rc_chan_count(0),
+ _rc_last_valid(0),
_task(-1),
_task_should_exit(false),
_mavlink_fd(-1),
- _perf_update(perf_alloc(PC_ELAPSED, "px4io update")),
+ _perf_update(perf_alloc(PC_ELAPSED, "io update")),
+ _perf_write(perf_alloc(PC_ELAPSED, "io write")),
+ _perf_chan_count(perf_alloc(PC_COUNT, "io rc #")),
_status(0),
_alarms(0),
- _t_actuators(-1),
- _t_armed(-1),
- _t_vstatus(-1),
+ _t_actuator_controls_0(-1),
+ _t_actuator_controls_1(-1),
+ _t_actuator_controls_2(-1),
+ _t_actuator_controls_3(-1),
+ _t_actuator_armed(-1),
+ _t_vehicle_control_mode(-1),
_t_param(-1),
+ _t_vehicle_command(-1),
_to_input_rc(0),
- _to_actuators_effective(0),
_to_outputs(0),
_to_battery(0),
- _battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
+ _to_servorail(0),
+ _to_safety(0),
+ _primary_pwm_device(false),
+ _lockdown_override(false),
+ _battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
_battery_mamphour_total(0),
- _battery_last_timestamp(0),
- _primary_pwm_device(false)
+ _battery_last_timestamp(0)
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ , _dsm_vcc_ctl(false)
+#endif
+
{
/* we need this potentially before it could be set in task_main */
g_dev = this;
- /* open MAVLink text channel */
- _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
-
- _debug_enabled = true;
+ _debug_enabled = false;
+ _servorail_status.rssi_v = 0;
}
PX4IO::~PX4IO()
@@ -356,10 +524,47 @@ PX4IO::~PX4IO()
if (_task != -1)
task_delete(_task);
+ if (_interface != nullptr)
+ delete _interface;
+
g_dev = nullptr;
}
int
+PX4IO::detect()
+{
+ int ret;
+
+ if (_task == -1) {
+
+ /* do regular cdev init */
+ ret = CDev::init();
+
+ if (ret != OK)
+ return ret;
+
+ /* get some parameters */
+ unsigned protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+
+ if (protocol != PX4IO_PROTOCOL_VERSION) {
+ if (protocol == _io_reg_get_error) {
+ log("IO not installed");
+
+ } else {
+ log("IO version error");
+ mavlink_log_emergency(_mavlink_fd, "IO VERSION MISMATCH, PLEASE UPGRADE SOFTWARE!");
+ }
+
+ return -1;
+ }
+ }
+
+ log("IO found");
+
+ return 0;
+}
+
+int
PX4IO::init()
{
int ret;
@@ -367,33 +572,43 @@ PX4IO::init()
ASSERT(_task == -1);
/* do regular cdev init */
- ret = I2C::init();
+ ret = CDev::init();
+
if (ret != OK)
return ret;
- /*
- * Enable a couple of retries for operations to IO.
- *
- * Register read/write operations are intentionally idempotent
- * so this is safe as designed.
- */
- _retries = 2;
-
/* get some parameters */
+ unsigned protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+
+ if (protocol == _io_reg_get_error) {
+ log("failed to communicate with IO");
+ mavlink_log_emergency(_mavlink_fd, "[IO] failed to communicate with IO, abort.");
+ return -1;
+ }
+
+ if (protocol != PX4IO_PROTOCOL_VERSION) {
+ log("protocol/firmware mismatch");
+ mavlink_log_emergency(_mavlink_fd, "[IO] protocol/firmware mismatch, abort.");
+ return -1;
+ }
+
+ _hardware = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION);
_max_actuators = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT);
- _max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
+ _max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
_max_relays = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT);
_max_transfer = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER) - 2;
_max_rc_input = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT);
+
if ((_max_actuators < 1) || (_max_actuators > 255) ||
- (_max_relays < 1) || (_max_relays > 255) ||
- (_max_transfer < 16) || (_max_transfer > 255) ||
+ (_max_relays > 32) ||
+ (_max_transfer < 16) || (_max_transfer > 255) ||
(_max_rc_input < 1) || (_max_rc_input > 255)) {
- log("failed getting parameters from PX4IO");
- mavlink_log_emergency(_mavlink_fd, "[IO] param read fail, abort.");
+ log("config read error");
+ mavlink_log_emergency(_mavlink_fd, "[IO] config read fail, abort.");
return -1;
}
+
if (_max_rc_input > RC_INPUT_MAX_CHANNELS)
_max_rc_input = RC_INPUT_MAX_CHANNELS;
@@ -408,6 +623,7 @@ PX4IO::init()
/* get IO's last seen FMU state */
ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, &reg, sizeof(reg));
+
if (ret != OK)
return ret;
@@ -418,27 +634,31 @@ PX4IO::init()
if ((reg & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) &&
(reg & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
- mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
+ /* get a status update from IO */
+ io_get_status();
+
+ mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
+ log("INAIR RESTART RECOVERY (needs commander app running)");
/* WARNING: COMMANDER app/vehicle status must be initialized.
* If this fails (or the app is not started), worst-case IO
* remains untouched (so manual override is still available).
*/
- int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_armed));
/* fill with initial values, clear updated flag */
- vehicle_status_s status;
+ struct actuator_armed_s safety;
uint64_t try_start_time = hrt_absolute_time();
bool updated = false;
-
- /* keep checking for an update, ensure we got a recent state,
+
+ /* keep checking for an update, ensure we got a arming information,
not something that was published a long time ago. */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
/* got data, copy and exit loop */
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_armed), safety_sub, &safety);
break;
}
@@ -446,7 +666,7 @@ PX4IO::init()
usleep(10000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 50000) {
+ if ((hrt_absolute_time() - try_start_time) / 1000 > 3000) {
log("failed to recover from in-air restart (1), aborting IO driver init.");
return 1;
}
@@ -464,52 +684,65 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- cmd.target_system = status.system_id;
- cmd.target_component = status.component_id;
- cmd.source_system = status.system_id;
- cmd.source_component = status.component_id;
+ // cmd.target_system = status.system_id;
+ // cmd.target_component = status.component_id;
+ // cmd.source_system = status.system_id;
+ // cmd.source_component = status.component_id;
/* ask to confirm command */
cmd.confirmation = 1;
/* send command once */
- (void)orb_advertise(ORB_ID(vehicle_command), &cmd);
+ orb_advert_t pub = orb_advertise(ORB_ID(vehicle_command), &cmd);
/* spin here until IO's state has propagated into the system */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_armed), safety_sub, &safety);
}
- /* wait 10 ms */
- usleep(10000);
+ /* wait 50 ms */
+ usleep(50000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 50000) {
+ if ((hrt_absolute_time() - try_start_time) / 1000 > 2000) {
log("failed to recover from in-air restart (2), aborting IO driver init.");
return 1;
}
- /* keep waiting for state change for 10 s */
- } while (!status.flag_system_armed);
+ /* re-send if necessary */
+ if (!safety.armed) {
+ orb_publish(ORB_ID(vehicle_command), pub, &cmd);
+ log("re-sending arm cmd");
+ }
- /* regular boot, no in-air restart, init IO */
- } else {
+ /* keep waiting for state change for 2 s */
+ } while (!safety.armed);
+ /* regular boot, no in-air restart, init IO */
+
+ } else {
/* dis-arm IO before touching anything */
- io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
- PX4IO_P_SETUP_ARMING_FMU_ARMED |
- PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
- PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0);
+ io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
+ PX4IO_P_SETUP_ARMING_FMU_ARMED |
+ PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
+ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, 0);
- /* publish RC config to IO */
- ret = io_set_rc_config();
- if (ret != OK) {
- log("failed to update RC input config");
- mavlink_log_info(_mavlink_fd, "[IO] RC config upload fail");
- return ret;
+ if (_rc_handling_disabled) {
+ ret = io_disable_rc_handling();
+
+ } else {
+ /* publish RC config to IO */
+ ret = io_set_rc_config();
+
+ if (ret != OK) {
+ log("failed to update RC input config");
+ mavlink_log_info(_mavlink_fd, "[IO] RC config upload fail");
+ return ret;
+ }
}
}
@@ -523,7 +756,7 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -544,39 +777,41 @@ PX4IO::task_main_trampoline(int argc, char *argv[])
void
PX4IO::task_main()
{
- hrt_abstime last_poll_time = 0;
+ hrt_abstime poll_last = 0;
+ hrt_abstime orb_check_last = 0;
- log("starting");
+ _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
*/
- _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1));
- orb_set_interval(_t_actuators, 20); /* default to 50Hz */
-
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
-
- _t_vstatus = orb_subscribe(ORB_ID(vehicle_status));
- orb_set_interval(_t_vstatus, 200); /* 5Hz update rate max. */
-
+ _t_actuator_controls_0 = orb_subscribe(ORB_ID(actuator_controls_0));
+ orb_set_interval(_t_actuator_controls_0, 20); /* default to 50Hz */
+ _t_actuator_controls_1 = orb_subscribe(ORB_ID(actuator_controls_1));
+ orb_set_interval(_t_actuator_controls_1, 33); /* default to 30Hz */
+ _t_actuator_controls_2 = orb_subscribe(ORB_ID(actuator_controls_2));
+ orb_set_interval(_t_actuator_controls_2, 33); /* default to 30Hz */
+ _t_actuator_controls_3 = orb_subscribe(ORB_ID(actuator_controls_3));
+ orb_set_interval(_t_actuator_controls_3, 33); /* default to 30Hz */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ _t_vehicle_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
_t_param = orb_subscribe(ORB_ID(parameter_update));
- orb_set_interval(_t_param, 500); /* 2Hz update rate max. */
+ _t_vehicle_command = orb_subscribe(ORB_ID(vehicle_command));
+
+ if ((_t_actuator_controls_0 < 0) ||
+ (_t_actuator_armed < 0) ||
+ (_t_vehicle_control_mode < 0) ||
+ (_t_param < 0) ||
+ (_t_vehicle_command < 0)) {
+ log("subscription(s) failed");
+ goto out;
+ }
/* poll descriptor */
- pollfd fds[4];
- fds[0].fd = _t_actuators;
+ pollfd fds[1];
+ fds[0].fd = _t_actuator_controls_0;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
- fds[1].events = POLLIN;
- fds[2].fd = _t_vstatus;
- fds[2].events = POLLIN;
- fds[3].fd = _t_param;
- fds[3].events = POLLIN;
-
- debug("ready");
/* lock against the ioctl handler */
lock();
@@ -586,17 +821,23 @@ PX4IO::task_main()
/* adjust update interval */
if (_update_interval != 0) {
- if (_update_interval < 5)
- _update_interval = 5;
+ if (_update_interval < UPDATE_INTERVAL_MIN)
+ _update_interval = UPDATE_INTERVAL_MIN;
+
if (_update_interval > 100)
_update_interval = 100;
- orb_set_interval(_t_actuators, _update_interval);
+
+ orb_set_interval(_t_actuator_controls_0, _update_interval);
+ /*
+ * NOT changing the rate of groups 1-3 here, because only attitude
+ * really needs to run fast.
+ */
_update_interval = 0;
}
/* sleep waiting for topic updates, but no more than 20ms */
unlock();
- int ret = ::poll(&fds[0], sizeof(fds) / sizeof(fds[0]), 20);
+ int ret = ::poll(fds, 1, 20);
lock();
/* this would be bad... */
@@ -609,51 +850,104 @@ PX4IO::task_main()
hrt_abstime now = hrt_absolute_time();
/* if we have new control data from the ORB, handle it */
- if (fds[0].revents & POLLIN)
- io_set_control_state();
+ if (fds[0].revents & POLLIN) {
- /* if we have an arming state update, handle it */
- if ((fds[1].revents & POLLIN) || (fds[2].revents & POLLIN))
- io_set_arming_state();
+ /* we're not nice to the lower-priority control groups and only check them
+ when the primary group updated (which is now). */
+ (void)io_set_control_groups();
+ }
- /*
- * If it's time for another tick of the polling status machine,
- * try it now.
- */
- if ((now - last_poll_time) >= 20000) {
+ if (now >= poll_last + IO_POLL_INTERVAL) {
+ /* run at 50Hz */
+ poll_last = now;
- /*
- * Pull status and alarms from IO.
- */
+ /* pull status and alarms from IO */
io_get_status();
- /*
- * Get raw R/C input from IO.
- */
+ /* get raw R/C input from IO */
io_publish_raw_rc();
- /*
- * Fetch mixed servo controls and PWM outputs from IO.
- *
- * XXX We could do this at a reduced rate in many/most cases.
- */
- io_publish_mixed_controls();
+ /* fetch PWM outputs from IO */
io_publish_pwm_outputs();
+ }
+
+ if (now >= orb_check_last + ORB_CHECK_INTERVAL) {
+ /* run at 5Hz */
+ orb_check_last = now;
+
+ /* try to claim the MAVLink log FD */
+ if (_mavlink_fd < 0)
+ _mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
+
+ /* check updates on uORB topics and handle it */
+ bool updated = false;
+
+ /* arming state */
+ orb_check(_t_actuator_armed, &updated);
+
+ if (!updated) {
+ orb_check(_t_vehicle_control_mode, &updated);
+ }
+
+ if (updated) {
+ io_set_arming_state();
+ }
+
+ /* vehicle command */
+ orb_check(_t_vehicle_command, &updated);
+
+ if (updated) {
+ struct vehicle_command_s cmd;
+ orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd);
+
+ // Check for a DSM pairing command
+ if (((int)cmd.command == VEHICLE_CMD_START_RX_PAIR) && ((int)cmd.param1 == 0)) {
+ dsm_bind_ioctl((int)cmd.param2);
+ }
+ }
/*
* If parameters have changed, re-send RC mappings to IO
*
* XXX this may be a bit spammy
*/
- if (fds[3].revents & POLLIN) {
- parameter_update_s pupdate;
+ orb_check(_t_param, &updated);
- /* copy to reset the notification */
+ if (updated) {
+ parameter_update_s pupdate;
orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
+ int32_t dsm_bind_val;
+ param_t dsm_bind_param;
+
+ /* see if bind parameter has been set, and reset it to -1 */
+ param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
+
+ if (dsm_bind_val > -1) {
+ dsm_bind_ioctl(dsm_bind_val);
+ dsm_bind_val = -1;
+ param_set(dsm_bind_param, &dsm_bind_val);
+ }
+
/* re-upload RC input config as it may have changed */
io_set_rc_config();
+
+ /* re-set the battery scaling */
+ int32_t voltage_scaling_val;
+ param_t voltage_scaling_param;
+
+ /* set battery voltage scaling */
+ param_get(voltage_scaling_param = param_find("BAT_V_SCALE_IO"), &voltage_scaling_val);
+
+ /* send scaling voltage to IO */
+ uint16_t scaling = voltage_scaling_val;
+ int pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE, &scaling, 1);
+
+ if (pret != OK) {
+ log("voltage scaling upload failed");
+ }
}
+
}
perf_end(_perf_update);
@@ -661,6 +955,7 @@ PX4IO::task_main()
unlock();
+out:
debug("exiting");
/* clean up the alternate device node */
@@ -673,48 +968,112 @@ PX4IO::task_main()
}
int
-PX4IO::io_set_control_state()
+PX4IO::io_set_control_groups()
+{
+ int ret = io_set_control_state(0);
+
+ /* send auxiliary control groups */
+ (void)io_set_control_state(1);
+ (void)io_set_control_state(2);
+ (void)io_set_control_state(3);
+
+ return ret;
+}
+
+int
+PX4IO::io_set_control_state(unsigned group)
{
actuator_controls_s controls; ///< actuator outputs
uint16_t regs[_max_actuators];
/* get controls */
- orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1), _t_actuators, &controls);
+ bool changed;
+
+ switch (group) {
+ case 0:
+ {
+ orb_check(_t_actuator_controls_0, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_0), _t_actuator_controls_0, &controls);
+ }
+ }
+ break;
+ case 1:
+ {
+ orb_check(_t_actuator_controls_1, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_1), _t_actuator_controls_1, &controls);
+ }
+ }
+ break;
+ case 2:
+ {
+ orb_check(_t_actuator_controls_2, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_2), _t_actuator_controls_2, &controls);
+ }
+ }
+ break;
+ case 3:
+ {
+ orb_check(_t_actuator_controls_3, &changed);
+
+ if (changed) {
+ orb_copy(ORB_ID(actuator_controls_3), _t_actuator_controls_3, &controls);
+ }
+ }
+ break;
+ }
+
+ if (!changed)
+ return -1;
for (unsigned i = 0; i < _max_controls; i++)
regs[i] = FLOAT_TO_REG(controls.control[i]);
/* copy values to registers in IO */
- return io_reg_set(PX4IO_PAGE_CONTROLS, 0, regs, _max_controls);
+ return io_reg_set(PX4IO_PAGE_CONTROLS, group * PX4IO_PROTOCOL_MAX_CONTROL_COUNT, regs, _max_controls);
}
+
int
PX4IO::io_set_arming_state()
{
actuator_armed_s armed; ///< system armed state
- vehicle_status_s vstatus; ///< overall system state
+ vehicle_control_mode_s control_mode; ///< vehicle_control_mode
- orb_copy(ORB_ID(actuator_armed), _t_armed, &armed);
- orb_copy(ORB_ID(vehicle_status), _t_vstatus, &vstatus);
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
+ orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
uint16_t set = 0;
uint16_t clear = 0;
- if (armed.armed && !armed.lockdown) {
+ 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 (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+
} else {
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
}
- if (vstatus.flag_external_manual_override_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;
}
@@ -723,6 +1082,21 @@ PX4IO::io_set_arming_state()
}
int
+PX4IO::disable_rc_handling()
+{
+ return io_disable_rc_handling();
+}
+
+int
+PX4IO::io_disable_rc_handling()
+{
+ uint16_t set = PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED;
+ uint16_t clear = 0;
+
+ return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
+}
+
+int
PX4IO::io_set_rc_config()
{
unsigned offset = 0;
@@ -735,8 +1109,10 @@ PX4IO::io_set_rc_config()
* assign RC_MAP_ROLL/PITCH/YAW/THROTTLE to the canonical
* controls.
*/
+
+ /* fill the mapping with an error condition triggering value */
for (unsigned i = 0; i < _max_rc_input; i++)
- input_map[i] = -1;
+ input_map[i] = UINT8_MAX;
/*
* NOTE: The indices for mapped channels are 1-based
@@ -744,25 +1120,29 @@ PX4IO::io_set_rc_config()
* autopilots / GCS'.
*/
param_get(param_find("RC_MAP_ROLL"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 0;
param_get(param_find("RC_MAP_PITCH"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 1;
param_get(param_find("RC_MAP_YAW"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 2;
param_get(param_find("RC_MAP_THROTTLE"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 3;
- ichan = 4;
- for (unsigned i = 0; i < _max_rc_input; i++)
- if (input_map[i] == -1)
- input_map[i] = ichan++;
+ param_get(param_find("RC_MAP_MODE_SW"), &ichan);
+
+ if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ input_map[ichan - 1] = 4;
/*
* Iterate all possible RC inputs.
@@ -814,6 +1194,7 @@ PX4IO::io_set_rc_config()
/* send channel config to IO */
ret = io_reg_set(PX4IO_PAGE_RC_CONFIG, offset, regs, PX4IO_P_RC_CONFIG_STRIDE);
+
if (ret != OK) {
log("rc config upload failed");
break;
@@ -840,14 +1221,15 @@ PX4IO::io_handle_status(uint16_t status)
*/
/* check for IO reset - force it back to armed if necessary */
- if (_status & PX4IO_P_STATUS_FLAGS_ARMED && !(status & PX4IO_P_STATUS_FLAGS_ARMED)
- && !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
+ if (_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF && !(status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ && !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the arming flag */
- ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_ARMED | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
+ ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_SAFETY_OFF | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
/* set new status */
_status = status;
- _status &= PX4IO_P_STATUS_FLAGS_ARMED;
+ _status &= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
+
} else if (!(_status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the sync flag */
@@ -862,9 +1244,48 @@ PX4IO::io_handle_status(uint16_t status)
_status = status;
}
+ /**
+ * Get and handle the safety status
+ */
+ struct safety_s safety;
+ safety.timestamp = hrt_absolute_time();
+
+ if (status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
+ safety.safety_off = true;
+ safety.safety_switch_available = true;
+
+ } else {
+ safety.safety_off = false;
+ safety.safety_switch_available = true;
+ }
+
+ /* lazily publish the safety status */
+ if (_to_safety > 0) {
+ orb_publish(ORB_ID(safety), _to_safety, &safety);
+
+ } else {
+ _to_safety = orb_advertise(ORB_ID(safety), &safety);
+ }
+
return ret;
}
+void
+PX4IO::dsm_bind_ioctl(int dsmMode)
+{
+ if (!(_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
+ mavlink_log_info(_mavlink_fd, "[IO] binding DSM%s RX", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "-X" : "-X8"));
+ int ret = ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
+
+ if (ret)
+ mavlink_log_critical(_mavlink_fd, "binding failed.");
+
+ } else {
+ mavlink_log_info(_mavlink_fd, "[IO] system armed, bind request rejected");
+ }
+}
+
+
int
PX4IO::io_handle_alarms(uint16_t alarms)
{
@@ -878,53 +1299,92 @@ PX4IO::io_handle_alarms(uint16_t alarms)
return 0;
}
+void
+PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
+{
+ /* only publish if battery has a valid minimum voltage */
+ if (vbatt <= 3300) {
+ return;
+ }
+
+ battery_status_s battery_status;
+ battery_status.timestamp = hrt_absolute_time();
+
+ /* voltage is scaled to mV */
+ battery_status.voltage_v = vbatt / 1000.0f;
+ battery_status.voltage_filtered_v = vbatt / 1000.0f;
+
+ /*
+ ibatt contains the raw ADC count, as 12 bit ADC
+ value, with full range being 3.3v
+ */
+ battery_status.current_a = ibatt * (3.3f / 4096.0f) * _battery_amp_per_volt;
+ battery_status.current_a += _battery_amp_bias;
+
+ /*
+ integrate battery over time to get total mAh used
+ */
+ if (_battery_last_timestamp != 0) {
+ _battery_mamphour_total += battery_status.current_a *
+ (battery_status.timestamp - _battery_last_timestamp) * 1.0e-3f / 3600;
+ }
+
+ battery_status.discharged_mah = _battery_mamphour_total;
+ _battery_last_timestamp = battery_status.timestamp;
+
+ /* lazily publish the battery voltage */
+ if (_to_battery > 0) {
+ orb_publish(ORB_ID(battery_status), _to_battery, &battery_status);
+
+ } else {
+ _to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
+ }
+}
+
+void
+PX4IO::io_handle_vservo(uint16_t vservo, uint16_t vrssi)
+{
+ _servorail_status.timestamp = hrt_absolute_time();
+
+ /* voltage is scaled to mV */
+ _servorail_status.voltage_v = vservo * 0.001f;
+ _servorail_status.rssi_v = vrssi * 0.001f;
+
+ /* lazily publish the servorail voltages */
+ if (_to_servorail > 0) {
+ orb_publish(ORB_ID(servorail_status), _to_servorail, &_servorail_status);
+
+ } else {
+ _to_servorail = orb_advertise(ORB_ID(servorail_status), &_servorail_status);
+ }
+}
+
int
PX4IO::io_get_status()
{
- uint16_t regs[4];
+ uint16_t regs[6];
int ret;
- /* get STATUS_FLAGS, STATUS_ALARMS, STATUS_VBATT, STATUS_IBATT in that order */
+ /* get
+ * STATUS_FLAGS, STATUS_ALARMS, STATUS_VBATT, STATUS_IBATT,
+ * STATUS_VSERVO, STATUS_VRSSI, STATUS_PRSSI
+ * in that order */
ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &regs[0], sizeof(regs) / sizeof(regs[0]));
+
if (ret != OK)
return ret;
io_handle_status(regs[0]);
io_handle_alarms(regs[1]);
- /* only publish if battery has a valid minimum voltage */
- if (regs[2] > 3300) {
- battery_status_s battery_status;
-
- battery_status.timestamp = hrt_absolute_time();
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ io_handle_battery(regs[2], regs[3]);
+#endif
- /* voltage is scaled to mV */
- battery_status.voltage_v = regs[2] / 1000.0f;
-
- /*
- regs[3] contains the raw ADC count, as 12 bit ADC
- value, with full range being 3.3v
- */
- battery_status.current_a = regs[3] * (3.3f/4096.0f) * _battery_amp_per_volt;
- battery_status.current_a += _battery_amp_bias;
-
- /*
- integrate battery over time to get total mAh used
- */
- if (_battery_last_timestamp != 0) {
- _battery_mamphour_total += battery_status.current_a *
- (battery_status.timestamp - _battery_last_timestamp) * 1.0e-3f / 3600;
- }
- battery_status.discharged_mah = _battery_mamphour_total;
- _battery_last_timestamp = battery_status.timestamp;
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ io_handle_vservo(regs[4], regs[5]);
+#endif
- /* lazily publish the battery voltage */
- if (_to_battery > 0) {
- orb_publish(ORB_ID(battery_status), _to_battery, &battery_status);
- } else {
- _to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
- }
- }
return ret;
}
@@ -932,114 +1392,102 @@ int
PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
{
uint32_t channel_count;
- int ret = OK;
+ int ret;
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
-
+
+ static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
+ uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
+
/*
- * XXX Because the channel count and channel data are fetched
- * separately, there is a risk of a race between the two
- * that could leave us with channel data and a count that
- * are out of sync.
- * Fixing this would require a guarantee of atomicity from
- * IO, and a single fetch for both count and channels.
- *
- * XXX Since IO has the input calibration info, we ought to be
- * able to get the pre-fixed-up controls directly.
+ * Read the channel count and the first 9 channels.
*
- * XXX can we do this more cheaply? If we knew we had DMA, it would
- * almost certainly be better to just get all the inputs...
+ * This should be the common case (9 channel R/C control being a reasonable upper bound).
*/
- channel_count = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT);
- if (channel_count == _io_reg_get_error)
- return -EIO;
- if (channel_count > RC_INPUT_MAX_CHANNELS)
- channel_count = RC_INPUT_MAX_CHANNELS;
- input_rc.channel_count = channel_count;
+ input_rc.timestamp_publication = hrt_absolute_time();
+
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, &regs[0], prolog + 9);
+
+ if (ret != OK)
+ return ret;
+
+ /*
+ * Get the channel count any any extra channels. This is no more expensive than reading the
+ * channel count once.
+ */
+ channel_count = regs[PX4IO_P_RAW_RC_COUNT];
+
+ if (channel_count != _rc_chan_count)
+ perf_count(_perf_chan_count);
+
+ _rc_chan_count = channel_count;
+
+ input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA];
+ input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI];
+ input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT];
+ input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT];
- if (channel_count > 0) {
- ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, input_rc.values, channel_count);
- if (ret == OK)
- input_rc.timestamp = hrt_absolute_time();
+ /* rc_lost has to be set before the call to this function */
+ if (!input_rc.rc_lost && !input_rc.rc_failsafe)
+ _rc_last_valid = input_rc.timestamp_publication;
+
+ input_rc.timestamp_last_signal = _rc_last_valid;
+
+ if (channel_count > 9) {
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, &regs[prolog + 9], channel_count - 9);
+
+ if (ret != OK)
+ return ret;
}
+ input_rc.channel_count = channel_count;
+ memcpy(input_rc.values, &regs[prolog], channel_count * 2);
+
return ret;
}
int
PX4IO::io_publish_raw_rc()
{
- /* if no raw RC, just don't publish */
- if (!(_status & PX4IO_P_STATUS_FLAGS_RC_OK))
- return OK;
/* fetch values from IO */
rc_input_values rc_val;
- rc_val.timestamp = hrt_absolute_time();
+
+ /* set the RC status flag ORDER MATTERS! */
+ rc_val.rc_lost = !(_status & PX4IO_P_STATUS_FLAGS_RC_OK);
int ret = io_get_raw_rc_input(rc_val);
+
if (ret != OK)
return ret;
/* sort out the source of the values */
if (_status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
+
+ /* we do not know the RC input, only publish if RC OK flag is set */
+ /* if no raw RC, just don't publish */
+ if (!(_status & PX4IO_P_STATUS_FLAGS_RC_OK))
+ return OK;
}
/* lazily advertise on first publication */
if (_to_input_rc == 0) {
_to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_val);
- } else {
- orb_publish(ORB_ID(input_rc), _to_input_rc, &rc_val);
- }
-
- return OK;
-}
-int
-PX4IO::io_publish_mixed_controls()
-{
- /* if no FMU comms(!) just don't publish */
- if (!(_status & PX4IO_P_STATUS_FLAGS_FMU_OK))
- return OK;
-
- /* if not taking raw PPM from us, must be mixing */
- if (_status & PX4IO_P_STATUS_FLAGS_RAW_PWM)
- return OK;
-
- /* data we are going to fetch */
- actuator_controls_effective_s controls_effective;
- controls_effective.timestamp = hrt_absolute_time();
-
- /* get actuator controls from IO */
- uint16_t act[_max_actuators];
- int ret = io_reg_get(PX4IO_PAGE_ACTUATORS, 0, act, _max_actuators);
- if (ret != OK)
- return ret;
-
- /* convert from register format to float */
- for (unsigned i = 0; i < _max_actuators; i++)
- controls_effective.control_effective[i] = REG_TO_FLOAT(act[i]);
-
- /* laxily advertise on first publication */
- if (_to_actuators_effective == 0) {
- _to_actuators_effective =
- orb_advertise((_primary_pwm_device ?
- ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
- ORB_ID(actuator_controls_effective_1)),
- &controls_effective);
} else {
- orb_publish((_primary_pwm_device ?
- ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
- ORB_ID(actuator_controls_effective_1)),
- _to_actuators_effective, &controls_effective);
+ orb_publish(ORB_ID(input_rc), _to_input_rc, &rc_val);
}
return OK;
@@ -1059,26 +1507,29 @@ PX4IO::io_publish_pwm_outputs()
/* get servo values from IO */
uint16_t ctl[_max_actuators];
int ret = io_reg_get(PX4IO_PAGE_SERVOS, 0, ctl, _max_actuators);
+
if (ret != OK)
return ret;
/* convert from register format to float */
for (unsigned i = 0; i < _max_actuators; i++)
outputs.output[i] = ctl[i];
+
outputs.noutputs = _max_actuators;
/* lazily advertise on first publication */
if (_to_outputs == 0) {
_to_outputs = orb_advertise((_primary_pwm_device ?
- ORB_ID_VEHICLE_CONTROLS :
- ORB_ID(actuator_outputs_1)),
- &outputs);
+ ORB_ID_VEHICLE_CONTROLS :
+ ORB_ID(actuator_outputs_1)),
+ &outputs);
+
} else {
orb_publish((_primary_pwm_device ?
- ORB_ID_VEHICLE_CONTROLS :
- ORB_ID(actuator_outputs_1)),
- _to_outputs,
- &outputs);
+ ORB_ID_VEHICLE_CONTROLS :
+ ORB_ID(actuator_outputs_1)),
+ _to_outputs,
+ &outputs);
}
return OK;
@@ -1093,25 +1544,14 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned
return -EINVAL;
}
- /* set up the transfer */
- uint8_t addr[2] = {
- page,
- offset
- };
- i2c_msg_s msgv[2];
+ int ret = _interface->write((page << 8) | offset, (void *)values, num_values);
- msgv[0].flags = 0;
- msgv[0].buffer = addr;
- msgv[0].length = 2;
- msgv[1].flags = I2C_M_NORESTART;
- msgv[1].buffer = (uint8_t *)values;
- msgv[1].length = num_values * sizeof(*values);
+ if (ret != (int)num_values) {
+ debug("io_reg_set(%u,%u,%u): error %d", page, offset, num_values, ret);
+ return -1;
+ }
- /* perform the transfer */
- int ret = transfer(msgv, 2);
- if (ret != OK)
- debug("io_reg_set: error %d", ret);
- return ret;
+ return OK;
}
int
@@ -1123,25 +1563,20 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, uint16_t value)
int
PX4IO::io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_values)
{
- /* set up the transfer */
- uint8_t addr[2] = {
- page,
- offset
- };
- i2c_msg_s msgv[2];
+ /* range check the transfer */
+ if (num_values > ((_max_transfer) / sizeof(*values))) {
+ debug("io_reg_get: too many registers (%u, max %u)", num_values, _max_transfer / 2);
+ return -EINVAL;
+ }
- msgv[0].flags = 0;
- msgv[0].buffer = addr;
- msgv[0].length = 2;
- msgv[1].flags = I2C_M_READ;
- msgv[1].buffer = (uint8_t *)values;
- msgv[1].length = num_values * sizeof(*values);
+ int ret = _interface->read((page << 8) | offset, reinterpret_cast<void *>(values), num_values);
- /* perform the transfer */
- int ret = transfer(msgv, 2);
- if (ret != OK)
- debug("io_reg_get: data error %d", ret);
- return ret;
+ if (ret != (int)num_values) {
+ debug("io_reg_get(%u,%u,%u): data error %d", page, offset, num_values, ret);
+ return -1;
+ }
+
+ return OK;
}
uint32_t
@@ -1149,7 +1584,7 @@ PX4IO::io_reg_get(uint8_t page, uint8_t offset)
{
uint16_t value;
- if (io_reg_get(page, offset, &value, 1))
+ if (io_reg_get(page, offset, &value, 1) != OK)
return _io_reg_get_error;
return value;
@@ -1162,8 +1597,10 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
uint16_t value;
ret = io_reg_get(page, offset, &value, 1);
- if (ret)
+
+ if (ret != OK)
return ret;
+
value &= ~clearbits;
value |= setbits;
@@ -1171,61 +1608,160 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
}
int
-PX4IO::mixer_send(const char *buf, unsigned buflen)
+PX4IO::print_debug()
{
- uint8_t frame[_max_transfer];
- px4io_mixdata *msg = (px4io_mixdata *)&frame[0];
- unsigned max_len = _max_transfer - sizeof(px4io_mixdata);
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ int io_fd = -1;
- msg->f2i_mixer_magic = F2I_MIXER_MAGIC;
- msg->action = F2I_MIXER_ACTION_RESET;
+ if (io_fd < 0) {
+ io_fd = ::open("/dev/ttyS0", O_RDONLY | O_NONBLOCK | O_NOCTTY);
+ }
- do {
- unsigned count = buflen;
+ /* read IO's output */
+ if (io_fd > 0) {
+ pollfd fds[1];
+ fds[0].fd = io_fd;
+ fds[0].events = POLLIN;
- if (count > max_len)
- count = max_len;
+ usleep(500);
+ int pret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), 0);
- if (count > 0) {
- memcpy(&msg->text[0], buf, count);
- buf += count;
- buflen -= count;
- }
+ if (pret > 0) {
+ int count;
+ char buf[65];
- /*
- * We have to send an even number of bytes. This
- * will only happen on the very last transfer of a
- * mixer, and we are guaranteed that there will be
- * space left to round up as _max_transfer will be
- * even.
- */
- unsigned total_len = sizeof(px4io_mixdata) + count;
- if (total_len % 1) {
- msg->text[count] = '\0';
- total_len++;
+ do {
+ count = ::read(io_fd, buf, sizeof(buf) - 1);
+
+ if (count > 0) {
+ /* enforce null termination */
+ buf[count] = '\0';
+ warnx("IO CONSOLE: %s", buf);
+ }
+
+ } while (count > 0);
}
- int ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, total_len / 2);
+ ::close(io_fd);
+ return 0;
+ }
- if (ret) {
- log("mixer send error %d", ret);
- return ret;
+#endif
+ return 1;
+
+}
+
+int
+PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
+{
+ /* get debug level */
+ int debuglevel = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG);
+
+ uint8_t frame[_max_transfer];
+
+ do {
+
+ px4io_mixdata *msg = (px4io_mixdata *)&frame[0];
+ unsigned max_len = _max_transfer - sizeof(px4io_mixdata);
+
+ msg->f2i_mixer_magic = F2I_MIXER_MAGIC;
+ msg->action = F2I_MIXER_ACTION_RESET;
+
+ do {
+ unsigned count = buflen;
+
+ if (count > max_len)
+ count = max_len;
+
+ if (count > 0) {
+ memcpy(&msg->text[0], buf, count);
+ buf += count;
+ buflen -= count;
+
+ } else {
+ continue;
+ }
+
+ /*
+ * We have to send an even number of bytes. This
+ * will only happen on the very last transfer of a
+ * mixer, and we are guaranteed that there will be
+ * space left to round up as _max_transfer will be
+ * even.
+ */
+ unsigned total_len = sizeof(px4io_mixdata) + count;
+
+ if (total_len % 2) {
+ msg->text[count] = '\0';
+ total_len++;
+ }
+
+ int ret;
+
+ for (int i = 0; i < 30; i++) {
+ /* failed, but give it a 2nd shot */
+ ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, total_len / 2);
+
+ if (ret) {
+ usleep(333);
+ } else {
+ break;
+ }
+ }
+
+ /* print mixer chunk */
+ if (debuglevel > 5 || ret) {
+
+ warnx("fmu sent: \"%s\"", msg->text);
+
+ /* read IO's output */
+ print_debug();
+ }
+
+ if (ret) {
+ log("mixer send error %d", ret);
+ return ret;
+ }
+
+ msg->action = F2I_MIXER_ACTION_APPEND;
+
+ } while (buflen > 0);
+
+ /* ensure a closing newline */
+ msg->text[0] = '\n';
+ msg->text[1] = '\0';
+
+ int ret;
+
+ for (int i = 0; i < 30; i++) {
+ /* failed, but give it a 2nd shot */
+ ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, (sizeof(px4io_mixdata) + 2) / 2);
+
+ if (ret) {
+ usleep(333);
+ } else {
+ break;
+ }
}
- msg->action = F2I_MIXER_ACTION_APPEND;
+ if (ret)
+ return ret;
+
+ retries--;
+
+ log("mixer sent");
- } while (buflen > 0);
+ } while (retries > 0 && (!(io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK)));
/* check for the mixer-OK flag */
if (io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK) {
- debug("mixer upload OK");
mavlink_log_info(_mavlink_fd, "[IO] mixer upload ok");
return 0;
- } else {
- debug("mixer rejected by IO");
- mavlink_log_info(_mavlink_fd, "[IO] mixer upload fail");
}
+ log("mixer rejected by IO");
+ mavlink_log_info(_mavlink_fd, "[IO] mixer upload fail");
+
/* load must have failed for some reason */
return -EINVAL;
}
@@ -1234,123 +1770,195 @@ void
PX4IO::print_status()
{
/* basic configuration */
- printf("protocol %u software %u bootloader %u buffer %uB\n",
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_SOFTWARE_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_BOOTLOADER_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER));
+ printf("protocol %u hardware %u bootloader %u buffer %uB crc 0x%04x%04x\n",
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_BOOTLOADER_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_CRC),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_CRC+1));
printf("%u controls %u actuators %u R/C inputs %u analog inputs %u relays\n",
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT));
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT));
/* status */
printf("%u bytes free\n",
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
- printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s\n",
- flags,
- ((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) ? " DSM" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PPM" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
- ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"));
+ uint16_t io_status_flags = flags;
+ printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
+ flags,
+ ((flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
+ ((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PWM_PASSTHROUGH" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
+ ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : ""));
uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
- printf("alarms 0x%04x%s%s%s%s%s%s%s\n",
- alarms,
- ((alarms & PX4IO_P_STATUS_ALARMS_VBATT_LOW) ? " VBATT_LOW" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_TEMPERATURE) ? " TEMPERATURE" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_SERVO_CURRENT) ? " SERVO_CURRENT" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_ACC_CURRENT) ? " ACC_CURRENT" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""));
+ printf("alarms 0x%04x%s%s%s%s%s%s%s%s\n",
+ alarms,
+ ((alarms & PX4IO_P_STATUS_ALARMS_VBATT_LOW) ? " VBATT_LOW" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_TEMPERATURE) ? " TEMPERATURE" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_SERVO_CURRENT) ? " SERVO_CURRENT" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_ACC_CURRENT) ? " ACC_CURRENT" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_VSERVO_FAULT) ? " VSERVO_FAULT" : ""));
/* now clear alarms */
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, 0xFFFF);
- printf("vbatt %u ibatt %u vbatt scale %u\n",
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
- printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n",
- (double)_battery_amp_per_volt,
- (double)_battery_amp_bias,
- (double)_battery_mamphour_total);
+ if (_hardware == 1) {
+ printf("vbatt mV %u ibatt mV %u vbatt scale %u\n",
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
+ printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n",
+ (double)_battery_amp_per_volt,
+ (double)_battery_amp_bias,
+ (double)_battery_mamphour_total);
+
+ } else if (_hardware == 2) {
+ printf("vservo %u mV vservo scale %u\n",
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VSERVO),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VSERVO_SCALE));
+ printf("vrssi %u\n", io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VRSSI));
+ }
+
printf("actuators");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
+
printf("\n");
printf("servos");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_SERVOS, i));
+
printf("\n");
uint16_t raw_inputs = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT);
printf("%d raw R/C inputs", raw_inputs);
+
for (unsigned i = 0; i < raw_inputs; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + i));
+
printf("\n");
+
+ flags = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_FLAGS);
+ printf("R/C flags: 0x%04x%s%s%s%s%s\n", flags,
+ (((io_status_flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (!(flags & PX4IO_P_RAW_RC_FLAGS_RC_DSM11))) ? " DSM10" : ""),
+ (((io_status_flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (flags & PX4IO_P_RAW_RC_FLAGS_RC_DSM11)) ? " DSM11" : ""),
+ ((flags & PX4IO_P_RAW_RC_FLAGS_FRAME_DROP) ? " FRAME_DROP" : ""),
+ ((flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE) ? " FAILSAFE" : ""),
+ ((flags & PX4IO_P_RAW_RC_FLAGS_MAPPING_OK) ? " MAPPING_OK" : "")
+ );
+
+ if ((io_status_flags & PX4IO_P_STATUS_FLAGS_RC_PPM)) {
+ int frame_len = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_DATA);
+ printf("RC data (PPM frame len) %u us\n", frame_len);
+
+ if ((frame_len - raw_inputs * 2000 - 3000) < 0) {
+ printf("WARNING WARNING WARNING! This RC receiver does not allow safe frame detection.\n");
+ }
+ }
+
uint16_t mapped_inputs = io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_VALID);
printf("mapped R/C inputs 0x%04x", mapped_inputs);
+
for (unsigned i = 0; i < _max_rc_input; i++) {
if (mapped_inputs & (1 << i))
printf(" %u:%d", i, REG_TO_SIGNED(io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_BASE + i)));
}
+
printf("\n");
uint16_t adc_inputs = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT);
printf("ADC inputs");
+
for (unsigned i = 0; i < adc_inputs; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_ADC_INPUT, i));
+
printf("\n");
/* setup and state */
- printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES));
+ uint16_t features = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES);
+ printf("features 0x%04x%s%s%s%s\n", features,
+ ((features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) ? " S.BUS1_OUT" : ""),
+ ((features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) ? " S.BUS2_OUT" : ""),
+ ((features & PX4IO_P_SETUP_FEATURES_PWM_RSSI) ? " RSSI_PWM" : ""),
+ ((features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) ? " RSSI_ADC" : "")
+ );
uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
- printf("arming 0x%04x%s%s%s%s\n",
- arming,
- ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""));
+ printf("arming 0x%04x%s%s%s%s%s%s%s\n",
+ arming,
+ ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"),
+ ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"),
+ ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""));
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS));
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS));
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ printf("rates 0x%04x default %u alt %u\n",
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE));
+#endif
printf("debuglevel %u\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG));
printf("controls");
+
for (unsigned i = 0; i < _max_controls; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_CONTROLS, i));
+
printf("\n");
+
for (unsigned i = 0; i < _max_rc_input; i++) {
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
- i,
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
- options,
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
+ i,
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
+ options,
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
}
+
printf("failsafe");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+
+ printf("\ndisarmed values");
+
+ for (unsigned i = 0; i < _max_actuators; i++)
+ printf(" %u", io_reg_get(PX4IO_PAGE_DISARMED_PWM, i));
+
printf("\n");
}
int
-PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
+PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
+/* Make it obvious that file * isn't used here */
{
int ret = OK;
@@ -1376,92 +1984,269 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FMU_ARMED, 0);
break;
+ case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
+ /* get the default update rate */
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE);
+ break;
+
case PWM_SERVO_SET_UPDATE_RATE:
/* set the requested alternate rate */
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE, arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE: {
-
- /* blindly clear the PWM update alarm - might be set for some other reason */
- io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+ case PWM_SERVO_GET_UPDATE_RATE:
+ /* get the alternative update rate */
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE);
+ break;
- /* attempt to set the rate map */
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES, arg);
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE: {
- /* check that the changes took */
- uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
- if (alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) {
- ret = -EINVAL;
+ /* blindly clear the PWM update alarm - might be set for some other reason */
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+
+ /* attempt to set the rate map */
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES, arg);
+
+ /* check that the changes took */
+ uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
+
+ if (alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) {
+ ret = -EINVAL;
+ io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+ }
+
+ break;
}
+
+ case PWM_SERVO_GET_SELECT_UPDATE_RATE:
+
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES);
+ break;
+
+ case PWM_SERVO_SET_FAILSAFE_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ if (pwm->channel_count > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ ret = io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_FAILSAFE_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, 0, (uint16_t*)arg, _max_actuators);
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
+ case PWM_SERVO_SET_DISARMED_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ if (pwm->channel_count > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ ret = io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_DISARMED_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_DISARMED_PWM, 0, (uint16_t*)arg, _max_actuators);
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
+ case PWM_SERVO_SET_MIN_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ if (pwm->channel_count > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ ret = io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, pwm->values, pwm->channel_count);
break;
}
+ case PWM_SERVO_GET_MIN_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_CONTROL_MIN_PWM, 0, (uint16_t*)arg, _max_actuators);
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
+ case PWM_SERVO_SET_MAX_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ if (pwm->channel_count > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ ret = io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_MAX_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_CONTROL_MAX_PWM, 0, (uint16_t*)arg, _max_actuators);
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
case PWM_SERVO_GET_COUNT:
*(unsigned *)arg = _max_actuators;
break;
- case PWM_SERVO_SET(0) ... PWM_SERVO_SET(PWM_OUTPUT_MAX_CHANNELS - 1): {
+ case PWM_SERVO_SET_DISABLE_LOCKDOWN:
+ _lockdown_override = arg;
+ break;
- /* TODO: we could go lower for e.g. TurboPWM */
- unsigned channel = cmd - PWM_SERVO_SET(0);
- if ((channel >= _max_actuators) || (arg < 900) || (arg > 2100)) {
- ret = -EINVAL;
+ case PWM_SERVO_GET_DISABLE_LOCKDOWN:
+ *(unsigned *)arg = _lockdown_override;
+ break;
+
+ case DSM_BIND_START:
+
+ /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
+ if (arg == DSM2_BIND_PULSES ||
+ arg == DSMX_BIND_PULSES ||
+ arg == DSMX8_BIND_PULSES) {
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
+ usleep(500000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
+ usleep(72000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
+ usleep(50000);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
+
+ ret = OK;
} else {
- /* send a direct PWM value */
- ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, channel, arg);
+ ret = -EINVAL;
}
+ break;
+ case DSM_BIND_POWER_UP:
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
break;
- }
+
+ case PWM_SERVO_SET(0) ... PWM_SERVO_SET(PWM_OUTPUT_MAX_CHANNELS - 1): {
+
+ /* TODO: we could go lower for e.g. TurboPWM */
+ unsigned channel = cmd - PWM_SERVO_SET(0);
+
+ if ((channel >= _max_actuators) || (arg < PWM_LOWEST_MIN) || (arg > PWM_HIGHEST_MAX)) {
+ ret = -EINVAL;
+
+ } else {
+ /* send a direct PWM value */
+ ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, channel, arg);
+ }
+
+ break;
+ }
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(PWM_OUTPUT_MAX_CHANNELS - 1): {
- unsigned channel = cmd - PWM_SERVO_GET(0);
+ unsigned channel = cmd - PWM_SERVO_GET(0);
+
+ if (channel >= _max_actuators) {
+ ret = -EINVAL;
- if (channel >= _max_actuators) {
- ret = -EINVAL;
- } else {
- /* fetch a current PWM value */
- uint32_t value = io_reg_get(PX4IO_PAGE_SERVOS, channel);
- if (value == _io_reg_get_error) {
- ret = -EIO;
} else {
- *(servo_position_t *)arg = value;
+ /* fetch a current PWM value */
+ uint32_t value = io_reg_get(PX4IO_PAGE_SERVOS, channel);
+
+ if (value == _io_reg_get_error) {
+ ret = -EIO;
+
+ } else {
+ *(servo_position_t *)arg = value;
+ }
}
+
+ break;
}
- break;
- }
case PWM_SERVO_GET_RATEGROUP(0) ... PWM_SERVO_GET_RATEGROUP(PWM_OUTPUT_MAX_CHANNELS - 1): {
- unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
+ unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
- uint32_t value = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
+ *(uint32_t *)arg = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
- *(uint32_t *)arg = value;
- break;
- }
+ if (*(uint32_t *)arg == _io_reg_get_error)
+ ret = -EIO;
- case GPIO_RESET:
- ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0);
- break;
+ break;
+ }
+
+ case GPIO_RESET: {
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ uint32_t bits = (1 << _max_relays) - 1;
+
+ /* don't touch relay1 if it's controlling RX vcc */
+ if (_dsm_vcc_ctl)
+ bits &= ~PX4IO_P_SETUP_RELAYS_POWER1;
+
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, bits, 0);
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ ret = -EINVAL;
+#endif
+ break;
+ }
case GPIO_SET:
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
arg &= ((1 << _max_relays) - 1);
+
+ /* don't touch relay1 if it's controlling RX vcc */
+ if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1)) {
+ ret = -EINVAL;
+ break;
+ }
+
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0, arg);
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ ret = -EINVAL;
+#endif
break;
case GPIO_CLEAR:
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
arg &= ((1 << _max_relays) - 1);
+
+ /* don't touch relay1 if it's controlling RX vcc */
+ if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1)) {
+ ret = -EINVAL;
+ break;
+ }
+
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ ret = -EINVAL;
+#endif
break;
case GPIO_GET:
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
*(uint32_t *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS);
+
if (*(uint32_t *)arg == _io_reg_get_error)
ret = -EIO;
+
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ ret = -EINVAL;
+#endif
break;
case MIXERIOCGETOUTPUTCOUNT:
@@ -1473,53 +2258,115 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
break;
case MIXERIOCLOADBUF: {
- const char *buf = (const char *)arg;
- ret = mixer_send(buf, strnlen(buf, 1024));
- break;
- }
+ const char *buf = (const char *)arg;
+ ret = mixer_send(buf, strnlen(buf, 2048));
+ break;
+ }
case RC_INPUT_GET: {
- uint16_t status;
- rc_input_values *rc_val = (rc_input_values *)arg;
+ uint16_t status;
+ rc_input_values *rc_val = (rc_input_values *)arg;
- ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &status, 1);
- if (ret != OK)
- break;
+ ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &status, 1);
- /* if no R/C input, don't try to fetch anything */
- if (!(status & PX4IO_P_STATUS_FLAGS_RC_OK)) {
- ret = -ENOTCONN;
- break;
- }
+ if (ret != OK)
+ break;
- /* sort out the source of the values */
- if (status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_PPM;
- } else if (status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
- } else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
- } else {
- rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
- }
+ /* if no R/C input, don't try to fetch anything */
+ if (!(status & PX4IO_P_STATUS_FLAGS_RC_OK)) {
+ ret = -ENOTCONN;
+ break;
+ }
- /* read raw R/C input values */
- ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, &(rc_val->values[0]), _max_rc_input);
- break;
- }
+ /* sort out the source of the values */
+ if (status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+
+ } else {
+ rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
+ }
+
+ /* read raw R/C input values */
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, &(rc_val->values[0]), _max_rc_input);
+ break;
+ }
case PX4IO_SET_DEBUG:
/* set the debug level */
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG, arg);
break;
+ case PX4IO_REBOOT_BOOTLOADER:
+ if (system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ return -EINVAL;
+
+ /* reboot into bootloader - arg must be PX4IO_REBOOT_BL_MAGIC */
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_REBOOT_BL, arg);
+ // we don't expect a reply from this operation
+ ret = OK;
+ break;
+
+ case PX4IO_CHECK_CRC: {
+ /* check IO firmware CRC against passed value */
+ uint32_t io_crc = 0;
+ ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_CRC, (uint16_t *)&io_crc, 2);
+ if (ret != OK)
+ return ret;
+ if (io_crc != arg) {
+ debug("crc mismatch 0x%08x 0x%08x", (unsigned)io_crc, arg);
+ return -EINVAL;
+ }
+ break;
+ }
+
case PX4IO_INAIR_RESTART_ENABLE:
+
/* set/clear the 'in-air restart' bit */
if (arg) {
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK);
+
} else {
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK, 0);
}
+
+ break;
+
+ case RC_INPUT_ENABLE_RSSI_ANALOG:
+
+ if (arg) {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_ADC_RSSI);
+ } else {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, PX4IO_P_SETUP_FEATURES_ADC_RSSI, 0);
+ }
+
+ break;
+
+ case RC_INPUT_ENABLE_RSSI_PWM:
+
+ if (arg) {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_PWM_RSSI);
+ } else {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, PX4IO_P_SETUP_FEATURES_PWM_RSSI, 0);
+ }
+
+ break;
+
+ case SBUS_SET_PROTO_VERSION:
+
+ if (arg == 1) {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_SBUS1_OUT);
+ } else if (arg == 2) {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ } else {
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT), 0);
+ }
+
break;
default:
@@ -1531,17 +2378,24 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
}
ssize_t
-PX4IO::write(file *filp, const char *buffer, size_t len)
+PX4IO::write(file * /*filp*/, const char *buffer, size_t len)
+/* Make it obvious that file * isn't used here */
{
unsigned count = len / 2;
if (count > _max_actuators)
count = _max_actuators;
+
if (count > 0) {
+
+ perf_begin(_perf_write);
int ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, (uint16_t *)buffer, count);
+ perf_end(_perf_write);
+
if (ret != OK)
return ret;
}
+
return count * 2;
}
@@ -1549,8 +2403,9 @@ int
PX4IO::set_update_rate(int rate)
{
int interval_ms = 1000 / rate;
- if (interval_ms < 5) {
- interval_ms = 5;
+
+ if (interval_ms < UPDATE_INTERVAL_MIN) {
+ interval_ms = UPDATE_INTERVAL_MIN;
warnx("update rate too high, limiting interval to %d ms (%d Hz).", interval_ms, 1000 / interval_ms);
}
@@ -1575,27 +2430,224 @@ extern "C" __EXPORT int px4io_main(int argc, char *argv[]);
namespace
{
+device::Device *
+get_interface()
+{
+ device::Device *interface = nullptr;
+
+#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* try for a serial interface */
+ if (PX4IO_serial_interface != nullptr)
+ interface = PX4IO_serial_interface();
+
+ if (interface != nullptr)
+ goto got;
+
+#endif
+
+ /* try for an I2C interface if we haven't got a serial one */
+ if (PX4IO_i2c_interface != nullptr)
+ interface = PX4IO_i2c_interface();
+
+ if (interface != nullptr)
+ goto got;
+
+ errx(1, "cannot alloc interface");
+
+got:
+
+ if (interface->init() != OK) {
+ delete interface;
+ errx(1, "interface init failed");
+ }
+
+ return interface;
+}
+
void
start(int argc, char *argv[])
{
if (g_dev != nullptr)
- errx(1, "already loaded");
+ errx(0, "already loaded");
+
+ /* allocate the interface */
+ device::Device *interface = get_interface();
/* create the driver - it will set g_dev */
- (void)new PX4IO();
+ (void)new PX4IO(interface);
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
+ delete interface;
errx(1, "driver alloc failed");
+ }
if (OK != g_dev->init()) {
delete g_dev;
+ g_dev = nullptr;
errx(1, "driver init failed");
}
+ /* disable RC handling on request */
+ if (argc > 1) {
+ if (!strcmp(argv[1], "norc")) {
+
+ if (g_dev->disable_rc_handling())
+ warnx("Failed disabling RC handling");
+
+ } else {
+ warnx("unknown argument: %s", argv[1]);
+ }
+ }
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ int dsm_vcc_ctl;
+
+ if (param_get(param_find("RC_RL1_DSM_VCC"), &dsm_vcc_ctl) == OK) {
+ if (dsm_vcc_ctl) {
+ g_dev->set_dsm_vcc_ctl(true);
+ g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
+ }
+ }
+
+#endif
+ exit(0);
+}
+
+void
+detect(int argc, char *argv[])
+{
+ if (g_dev != nullptr)
+ errx(0, "already loaded");
+
+ /* allocate the interface */
+ device::Device *interface = get_interface();
+
+ /* create the driver - it will set g_dev */
+ (void)new PX4IO(interface);
+
+ if (g_dev == nullptr)
+ errx(1, "driver alloc failed");
+
+ int ret = g_dev->detect();
+
+ delete g_dev;
+ g_dev = nullptr;
+
+ if (ret) {
+ /* nonzero, error */
+ exit(1);
+
+ } else {
+ exit(0);
+ }
+}
+
+void
+checkcrc(int argc, char *argv[])
+{
+ bool keep_running = false;
+
+ if (g_dev == nullptr) {
+ /* allocate the interface */
+ device::Device *interface = get_interface();
+
+ /* create the driver - it will set g_dev */
+ (void)new PX4IO(interface);
+
+ if (g_dev == nullptr)
+ errx(1, "driver alloc failed");
+ } else {
+ /* its already running, don't kill the driver */
+ keep_running = true;
+ }
+
+ /*
+ check IO CRC against CRC of a file
+ */
+ if (argc < 2) {
+ printf("usage: px4io checkcrc filename\n");
+ exit(1);
+ }
+ int fd = open(argv[1], O_RDONLY);
+ if (fd == -1) {
+ printf("open of %s failed - %d\n", argv[1], errno);
+ exit(1);
+ }
+ const uint32_t app_size_max = 0xf000;
+ uint32_t fw_crc = 0;
+ uint32_t nbytes = 0;
+ while (true) {
+ uint8_t buf[16];
+ int n = read(fd, buf, sizeof(buf));
+ if (n <= 0) break;
+ fw_crc = crc32part(buf, n, fw_crc);
+ nbytes += n;
+ }
+ close(fd);
+ while (nbytes < app_size_max) {
+ uint8_t b = 0xff;
+ fw_crc = crc32part(&b, 1, fw_crc);
+ nbytes++;
+ }
+
+ int ret = g_dev->ioctl(nullptr, PX4IO_CHECK_CRC, fw_crc);
+
+ if (!keep_running) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ if (ret != OK) {
+ printf("check CRC failed - %d\n", ret);
+ exit(1);
+ }
+ printf("CRCs match\n");
exit(0);
}
void
+bind(int argc, char *argv[])
+{
+ int pulses;
+
+ if (g_dev == nullptr)
+ errx(1, "px4io must be started first");
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ if (!g_dev->get_dsm_vcc_ctl())
+ errx(1, "DSM bind feature not enabled");
+
+#endif
+
+ if (argc < 3)
+ errx(0, "needs argument, use dsm2, dsmx or dsmx8");
+
+ if (!strcmp(argv[2], "dsm2"))
+ pulses = DSM2_BIND_PULSES;
+ else if (!strcmp(argv[2], "dsmx"))
+ pulses = DSMX_BIND_PULSES;
+ else if (!strcmp(argv[2], "dsmx8"))
+ pulses = DSMX8_BIND_PULSES;
+ else
+ errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]);
+ // Test for custom pulse parameter
+ if (argc > 3)
+ pulses = atoi(argv[3]);
+ if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ errx(1, "system must not be armed");
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1.");
+#endif
+ g_dev->ioctl(nullptr, DSM_BIND_START, pulses);
+
+ exit(0);
+
+}
+
+void
test(void)
{
int fd;
@@ -1604,7 +2656,7 @@ test(void)
int direction = 1;
int ret;
- fd = open("/dev/px4io", O_WRONLY);
+ fd = open(PX4IO_DEVICE_PATH, O_WRONLY);
if (fd < 0)
err(1, "failed to open device");
@@ -1612,29 +2664,46 @@ test(void)
if (ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count))
err(1, "failed to get servo count");
+ /* tell IO that its ok to disable its safety with the switch */
+ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_ARM_OK");
+
if (ioctl(fd, PWM_SERVO_ARM, 0))
err(1, "failed to arm servos");
+ struct pollfd fds;
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
for (;;) {
/* sweep all servos between 1000..2000 */
servo_position_t servos[servo_count];
+
for (unsigned i = 0; i < servo_count; i++)
servos[i] = pwm_value;
ret = write(fd, servos, sizeof(servos));
+
if (ret != (int)sizeof(servos))
err(1, "error writing PWM servo data, wrote %u got %d", sizeof(servos), ret);
if (direction > 0) {
if (pwm_value < 2000) {
pwm_value++;
+
} else {
direction = -1;
}
+
} else {
if (pwm_value > 1000) {
pwm_value--;
+
} else {
direction = 1;
}
@@ -1646,42 +2715,137 @@ test(void)
if (ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&value))
err(1, "error reading PWM servo %d", i);
+
if (value != servos[i])
errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
}
+
+ /* Check if user wants to quit */
+ char c;
+ ret = poll(&fds, 1, 0);
+
+ if (ret > 0) {
+
+ read(0, &c, 1);
+
+ if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("User abort\n");
+ exit(0);
+ }
+ }
}
}
void
monitor(void)
{
- unsigned cancels = 3;
- printf("Hit <enter> three times to exit monitor mode\n");
+ /* clear screen */
+ printf("\033[2J");
+
+ unsigned cancels = 2;
for (;;) {
pollfd fds[1];
fds[0].fd = 0;
fds[0].events = POLLIN;
- poll(fds, 1, 500);
+ poll(fds, 1, 2000);
if (fds[0].revents == POLLIN) {
int c;
read(0, &c, 1);
- if (cancels-- == 0)
+ if (cancels-- == 0) {
+ printf("\033[2J\033[H"); /* move cursor home and clear screen */
exit(0);
+ }
}
-#warning implement this
+ if (g_dev != nullptr) {
+
+ printf("\033[2J\033[H"); /* move cursor home and clear screen */
+ (void)g_dev->print_status();
+ (void)g_dev->print_debug();
+ printf("\n\n\n[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
-// if (g_dev != nullptr)
-// g_dev->dump_one = true;
+ } else {
+ errx(1, "driver not loaded, exiting");
+ }
}
}
+void
+if_test(unsigned mode)
+{
+ device::Device *interface = get_interface();
+ int result;
+
+ if (interface) {
+ result = interface->ioctl(1, mode); /* XXX magic numbers */
+ delete interface;
+ } else {
+ errx(1, "interface not loaded, exiting");
+ }
+
+ errx(0, "test returned %d", result);
}
+void
+lockdown(int argc, char *argv[])
+{
+ if (g_dev != nullptr) {
+
+ if (argc > 2 && !strcmp(argv[2], "disable")) {
+
+ warnx("WARNING: ACTUATORS WILL BE LIVE IN HIL! PROCEED?");
+ warnx("Press 'y' to enable, any other key to abort.");
+
+ /* check if user wants to abort */
+ char c;
+
+ struct pollfd fds;
+ int ret;
+ hrt_abstime start = hrt_absolute_time();
+ const unsigned long timeout = 5000000;
+
+ while (hrt_elapsed_time(&start) < timeout) {
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 0);
+
+ if (ret > 0) {
+
+ read(0, &c, 1);
+
+ if (c != 'y') {
+ exit(0);
+ } else if (c == 'y') {
+ break;
+ }
+ }
+
+ usleep(10000);
+ }
+
+ if (hrt_elapsed_time(&start) > timeout)
+ errx(1, "TIMEOUT! ABORTED WITHOUT CHANGES.");
+
+ (void)g_dev->ioctl(0, PWM_SERVO_SET_DISABLE_LOCKDOWN, 1);
+
+ warnx("WARNING: ACTUATORS ARE NOW LIVE IN HIL!");
+ } else {
+ (void)g_dev->ioctl(0, PWM_SERVO_SET_DISABLE_LOCKDOWN, 0);
+ warnx("ACTUATORS ARE NOW SAFE IN HIL.");
+ }
+
+ } else {
+ errx(1, "driver not loaded, exiting");
+ }
+ exit(0);
+}
+
+} /* namespace */
+
int
px4io_main(int argc, char *argv[])
{
@@ -1692,67 +2856,181 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "start"))
start(argc - 1, argv + 1);
- if (!strcmp(argv[1], "limit")) {
+ if (!strcmp(argv[1], "detect"))
+ detect(argc - 1, argv + 1);
+
+ if (!strcmp(argv[1], "checkcrc"))
+ checkcrc(argc - 1, argv + 1);
+
+ if (!strcmp(argv[1], "update")) {
if (g_dev != nullptr) {
+ printf("[px4io] loaded, detaching first\n");
+ /* stop the driver */
+ delete g_dev;
+ g_dev = nullptr;
+ }
- if ((argc > 2)) {
- g_dev->set_update_rate(atoi(argv[2]));
- } else {
- errx(1, "missing argument (50 - 200 Hz)");
- return 1;
- }
+ PX4IO_Uploader *up;
+ const char *fn[4];
+
+ /* work out what we're uploading... */
+ if (argc > 2) {
+ fn[0] = argv[2];
+ fn[1] = nullptr;
+
+ } else {
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ fn[0] = "/etc/extras/px4io-v1_default.bin";
+ fn[1] = "/fs/microsd/px4io1.bin";
+ fn[2] = "/fs/microsd/px4io.bin";
+ fn[3] = nullptr;
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ fn[0] = "/etc/extras/px4io-v2_default.bin";
+ fn[1] = "/fs/microsd/px4io2.bin";
+ fn[2] = "/fs/microsd/px4io.bin";
+ fn[3] = nullptr;
+#else
+#error "unknown board"
+#endif
}
- exit(0);
+
+ up = new PX4IO_Uploader;
+ int ret = up->upload(&fn[0]);
+ delete up;
+
+ switch (ret) {
+ case OK:
+ break;
+
+ case -ENOENT:
+ errx(1, "PX4IO firmware file not found");
+
+ case -EEXIST:
+ case -EIO:
+ errx(1, "error updating PX4IO - check that bootloader mode is enabled");
+
+ case -EINVAL:
+ errx(1, "verify failed - retry the update");
+
+ case -ETIMEDOUT:
+ errx(1, "timed out waiting for bootloader - power-cycle and try again");
+
+ default:
+ errx(1, "unexpected error %d", ret);
+ }
+
+ return ret;
}
- if (!strcmp(argv[1], "current")) {
- if (g_dev != nullptr) {
- if ((argc > 3)) {
- g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3]));
- } else {
- errx(1, "missing argument (apm_per_volt, amp_offset)");
- return 1;
+ if (!strcmp(argv[1], "iftest")) {
+ if (g_dev != nullptr)
+ errx(1, "can't iftest when started");
+
+ if_test((argc > 2) ? strtol(argv[2], NULL, 0) : 0);
+ }
+
+ if (!strcmp(argv[1], "forceupdate")) {
+ /*
+ force update of the IO firmware without requiring
+ the user to hold the safety switch down
+ */
+ if (argc <= 3) {
+ warnx("usage: px4io forceupdate MAGIC filename");
+ exit(1);
+ }
+ if (g_dev == nullptr) {
+ warnx("px4io is not started, still attempting upgrade");
+
+ /* allocate the interface */
+ device::Device *interface = get_interface();
+
+ /* create the driver - it will set g_dev */
+ (void)new PX4IO(interface);
+
+ if (g_dev == nullptr) {
+ delete interface;
+ errx(1, "driver alloc failed");
}
}
+
+ uint16_t arg = atol(argv[2]);
+ int ret = g_dev->ioctl(nullptr, PX4IO_REBOOT_BOOTLOADER, arg);
+ if (ret != OK) {
+ printf("reboot failed - %d\n", ret);
+ exit(1);
+ }
+
+ // tear down the px4io instance
+ delete g_dev;
+ g_dev = nullptr;
+
+ // upload the specified firmware
+ const char *fn[2];
+ fn[0] = argv[3];
+ fn[1] = nullptr;
+ PX4IO_Uploader *up = new PX4IO_Uploader;
+ up->upload(&fn[0]);
+ delete up;
exit(0);
}
- if (!strcmp(argv[1], "recovery")) {
+ /* commands below here require a started driver */
+
+ if (g_dev == nullptr)
+ errx(1, "not started");
+
+ if (!strcmp(argv[1], "limit")) {
+
+ if ((argc > 2)) {
+ g_dev->set_update_rate(atoi(argv[2]));
- if (g_dev != nullptr) {
- /*
- * Enable in-air restart support.
- * We can cheat and call the driver directly, as it
- * doesn't reference filp in ioctl()
- */
- g_dev->ioctl(NULL, PX4IO_INAIR_RESTART_ENABLE, 1);
} else {
- errx(1, "not loaded");
+ errx(1, "missing argument (50 - 500 Hz)");
+ return 1;
}
+
exit(0);
}
- if (!strcmp(argv[1], "stop")) {
+ if (!strcmp(argv[1], "current")) {
+ if ((argc > 3)) {
+ g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3]));
- if (g_dev != nullptr) {
- /* stop the driver */
- delete g_dev;
} else {
- errx(1, "not loaded");
+ errx(1, "missing argument (apm_per_volt, amp_offset)");
+ return 1;
}
+
+ exit(0);
+ }
+
+
+
+ if (!strcmp(argv[1], "recovery")) {
+
+ /*
+ * Enable in-air restart support.
+ * We can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ g_dev->ioctl(NULL, PX4IO_INAIR_RESTART_ENABLE, 1);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+
+ /* stop the driver */
+ delete g_dev;
+ g_dev = nullptr;
exit(0);
}
if (!strcmp(argv[1], "status")) {
- if (g_dev != nullptr) {
- printf("[px4io] loaded\n");
- g_dev->print_status();
- } else {
- printf("[px4io] not loaded\n");
- }
+ printf("[px4io] loaded\n");
+ g_dev->print_status();
exit(0);
}
@@ -1762,88 +3040,100 @@ px4io_main(int argc, char *argv[])
printf("usage: px4io debug LEVEL\n");
exit(1);
}
+
if (g_dev == nullptr) {
printf("px4io is not started\n");
exit(1);
}
+
uint8_t level = atoi(argv[2]);
/* we can cheat and call the driver directly, as it
* doesn't reference filp in ioctl()
*/
- int ret = g_dev->ioctl(NULL, PX4IO_SET_DEBUG, level);
+ int ret = g_dev->ioctl(nullptr, PX4IO_SET_DEBUG, level);
+
if (ret != 0) {
printf("SET_DEBUG failed - %d\n", ret);
exit(1);
}
+
printf("SET_DEBUG %u OK\n", (unsigned)level);
exit(0);
}
- /* note, stop not currently implemented */
+ if (!strcmp(argv[1], "rx_dsm") ||
+ !strcmp(argv[1], "rx_dsm_10bit") ||
+ !strcmp(argv[1], "rx_dsm_11bit") ||
+ !strcmp(argv[1], "rx_sbus") ||
+ !strcmp(argv[1], "rx_ppm"))
+ errx(0, "receiver type is automatically detected, option '%s' is deprecated", argv[1]);
- if (!strcmp(argv[1], "update")) {
+ if (!strcmp(argv[1], "test"))
+ test();
- if (g_dev != nullptr) {
- printf("[px4io] loaded, detaching first\n");
- /* stop the driver */
- delete g_dev;
- }
+ if (!strcmp(argv[1], "monitor"))
+ monitor();
- PX4IO_Uploader *up;
- const char *fn[3];
+ if (!strcmp(argv[1], "bind"))
+ bind(argc, argv);
- /* work out what we're uploading... */
- if (argc > 2) {
- fn[0] = argv[2];
- fn[1] = nullptr;
+ if (!strcmp(argv[1], "lockdown"))
+ lockdown(argc, argv);
- } else {
- fn[0] = "/fs/microsd/px4io.bin";
- fn[1] = "/etc/px4io.bin";
- fn[2] = nullptr;
- }
+ if (!strcmp(argv[1], "sbus1_out")) {
+ /* we can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ int ret = g_dev->ioctl(nullptr, SBUS_SET_PROTO_VERSION, 1);
- up = new PX4IO_Uploader;
- int ret = up->upload(&fn[0]);
- delete up;
+ if (ret != 0) {
+ errx(ret, "S.BUS v1 failed");
+ }
- switch (ret) {
- case OK:
- break;
+ exit(0);
+ }
- case -ENOENT:
- errx(1, "PX4IO firmware file not found");
+ if (!strcmp(argv[1], "sbus2_out")) {
+ /* we can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ int ret = g_dev->ioctl(nullptr, SBUS_SET_PROTO_VERSION, 2);
- case -EEXIST:
- case -EIO:
- errx(1, "error updating PX4IO - check that bootloader mode is enabled");
+ if (ret != 0) {
+ errx(ret, "S.BUS v2 failed");
+ }
- case -EINVAL:
- errx(1, "verify failed - retry the update");
+ exit(0);
+ }
- case -ETIMEDOUT:
- errx(1, "timed out waiting for bootloader - power-cycle and try again");
+ if (!strcmp(argv[1], "rssi_analog")) {
+ /* we can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ int ret = g_dev->ioctl(nullptr, RC_INPUT_ENABLE_RSSI_ANALOG, 1);
- default:
- errx(1, "unexpected error %d", ret);
+ if (ret != 0) {
+ errx(ret, "RSSI analog failed");
}
- return ret;
+ exit(0);
}
- if (!strcmp(argv[1], "rx_dsm") ||
- !strcmp(argv[1], "rx_dsm_10bit") ||
- !strcmp(argv[1], "rx_dsm_11bit") ||
- !strcmp(argv[1], "rx_sbus") ||
- !strcmp(argv[1], "rx_ppm"))
- errx(0, "receiver type is automatically detected, option '%s' is deprecated", argv[1]);
+ if (!strcmp(argv[1], "rssi_pwm")) {
+ /* we can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ int ret = g_dev->ioctl(nullptr, RC_INPUT_ENABLE_RSSI_PWM, 1);
- if (!strcmp(argv[1], "test"))
- test();
+ if (ret != 0) {
+ errx(ret, "RSSI PWM failed");
+ }
- if (!strcmp(argv[1], "monitor"))
- monitor();
+ exit(0);
+ }
- out:
- errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current' or 'update'");
+out:
+ errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug <level>',\n"
+ "'recovery', 'limit <rate>', 'current', 'bind', 'checkcrc',\n"
+ "'forceupdate', 'update', 'sbus1_out', 'sbus2_out', 'rssi_analog' or 'rssi_pwm'");
}
diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp
new file mode 100644
index 000000000..19776c40a
--- /dev/null
+++ b/src/drivers/px4io/px4io_i2c.cpp
@@ -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 px4io_i2c.cpp
+ *
+ * I2C interface for PX4IO
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+#include <board_config.h>
+
+#include <drivers/device/i2c.h>
+
+#ifdef PX4_I2C_OBDEV_PX4IO
+
+device::Device *PX4IO_i2c_interface();
+
+class PX4IO_I2C : public device::I2C
+{
+public:
+ PX4IO_I2C(int bus, uint8_t address);
+ virtual ~PX4IO_I2C();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count = 1);
+ virtual int write(unsigned address, void *data, unsigned count = 1);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+
+};
+
+device::Device
+*PX4IO_i2c_interface()
+{
+ return new PX4IO_I2C(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO);
+}
+
+PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
+ I2C("PX4IO_i2c", nullptr, bus, address, 320000)
+{
+ _retries = 3;
+}
+
+PX4IO_I2C::~PX4IO_I2C()
+{
+}
+
+int
+PX4IO_I2C::init()
+{
+ int ret;
+
+ ret = I2C::init();
+ if (ret != OK)
+ goto out;
+
+ /* XXX really should do something more here */
+
+out:
+ return 0;
+}
+
+int
+PX4IO_I2C::ioctl(unsigned operation, unsigned &arg)
+{
+ return 0;
+}
+
+int
+PX4IO_I2C::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ /* set up the transfer */
+ uint8_t addr[2] = {
+ page,
+ offset
+ };
+
+ i2c_msg_s msgv[2];
+
+ msgv[0].flags = 0;
+ msgv[0].buffer = addr;
+ msgv[0].length = 2;
+
+ msgv[1].flags = I2C_M_NORESTART;
+ msgv[1].buffer = (uint8_t *)values;
+ msgv[1].length = 2 * count;
+
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
+}
+
+int
+PX4IO_I2C::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ /* set up the transfer */
+ uint8_t addr[2] = {
+ page,
+ offset
+ };
+ i2c_msg_s msgv[2];
+
+ msgv[0].flags = 0;
+ msgv[0].buffer = addr;
+ msgv[0].length = 2;
+
+ msgv[1].flags = I2C_M_READ;
+ msgv[1].buffer = (uint8_t *)values;
+ msgv[1].length = 2 * count;
+
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
+}
+
+#endif /* PX4_I2C_OBDEV_PX4IO */
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
new file mode 100644
index 000000000..43318ca84
--- /dev/null
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -0,0 +1,679 @@
+/****************************************************************************
+ *
+ * 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 px4io_serial.cpp
+ *
+ * Serial interface for PX4IO
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#include <arch/board/board.h>
+
+/* XXX might be able to prune these */
+#include <nuttx/arch.h>
+#include <chip.h>
+#include <up_internal.h>
+#include <up_arch.h>
+
+#include <debug.h>
+
+#include <drivers/device/device.h>
+#include <drivers/drv_hrt.h>
+#include <board_config.h>
+
+#include <systemlib/perf_counter.h>
+
+#include <modules/px4iofirmware/protocol.h>
+
+#ifdef PX4IO_SERIAL_BASE
+
+device::Device *PX4IO_serial_interface();
+
+/* serial register accessors */
+#define REG(_x) (*(volatile uint32_t *)(PX4IO_SERIAL_BASE + _x))
+#define rSR REG(STM32_USART_SR_OFFSET)
+#define rDR REG(STM32_USART_DR_OFFSET)
+#define rBRR REG(STM32_USART_BRR_OFFSET)
+#define rCR1 REG(STM32_USART_CR1_OFFSET)
+#define rCR2 REG(STM32_USART_CR2_OFFSET)
+#define rCR3 REG(STM32_USART_CR3_OFFSET)
+#define rGTPR REG(STM32_USART_GTPR_OFFSET)
+
+class PX4IO_serial : public device::Device
+{
+public:
+ PX4IO_serial();
+ virtual ~PX4IO_serial();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count = 1);
+ virtual int write(unsigned address, void *data, unsigned count = 1);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+ /*
+ * XXX tune this value
+ *
+ * At 1.5Mbps each register takes 13.3µs, and we always transfer a full packet.
+ * Packet overhead is 26µs for the four-byte header.
+ *
+ * 32 registers = 451µs
+ *
+ * Maybe we can just send smaller packets (e.g. 8 regs) and loop for larger (less common)
+ * transfers? Could cause issues with any regs expecting to be written atomically...
+ */
+ static IOPacket _dma_buffer; // XXX static to ensure DMA-able memory
+
+ DMA_HANDLE _tx_dma;
+ DMA_HANDLE _rx_dma;
+
+ /** saved DMA status */
+ static const unsigned _dma_status_inactive = 0x80000000; // low bits overlap DMA_STATUS_* values
+ static const unsigned _dma_status_waiting = 0x00000000;
+ volatile unsigned _rx_dma_status;
+
+ /** bus-ownership lock */
+ sem_t _bus_semaphore;
+
+ /** client-waiting lock/signal */
+ sem_t _completion_semaphore;
+
+ /**
+ * Start the transaction with IO and wait for it to complete.
+ */
+ int _wait_complete();
+
+ /**
+ * DMA completion handler.
+ */
+ static void _dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
+ void _do_rx_dma_callback(unsigned status);
+
+ /**
+ * Serial interrupt handler.
+ */
+ static int _interrupt(int vector, void *context);
+ void _do_interrupt();
+
+ /**
+ * Cancel any DMA in progress with an error.
+ */
+ void _abort_dma();
+
+ /**
+ * Performance counters.
+ */
+ perf_counter_t _pc_txns;
+ perf_counter_t _pc_dmasetup;
+ perf_counter_t _pc_retries;
+ perf_counter_t _pc_timeouts;
+ perf_counter_t _pc_crcerrs;
+ perf_counter_t _pc_dmaerrs;
+ perf_counter_t _pc_protoerrs;
+ perf_counter_t _pc_uerrs;
+ perf_counter_t _pc_idle;
+ perf_counter_t _pc_badidle;
+
+};
+
+IOPacket PX4IO_serial::_dma_buffer;
+static PX4IO_serial *g_interface;
+
+device::Device
+*PX4IO_serial_interface()
+{
+ return new PX4IO_serial();
+}
+
+PX4IO_serial::PX4IO_serial() :
+ Device("PX4IO_serial"),
+ _tx_dma(nullptr),
+ _rx_dma(nullptr),
+ _rx_dma_status(_dma_status_inactive),
+ _pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")),
+ _pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
+ _pc_retries(perf_alloc(PC_COUNT, "io_retries ")),
+ _pc_timeouts(perf_alloc(PC_COUNT, "io_timeouts ")),
+ _pc_crcerrs(perf_alloc(PC_COUNT, "io_crcerrs ")),
+ _pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs ")),
+ _pc_protoerrs(perf_alloc(PC_COUNT, "io_protoerrs")),
+ _pc_uerrs(perf_alloc(PC_COUNT, "io_uarterrs ")),
+ _pc_idle(perf_alloc(PC_COUNT, "io_idle ")),
+ _pc_badidle(perf_alloc(PC_COUNT, "io_badidle "))
+{
+ g_interface = this;
+}
+
+PX4IO_serial::~PX4IO_serial()
+{
+ if (_tx_dma != nullptr) {
+ stm32_dmastop(_tx_dma);
+ stm32_dmafree(_tx_dma);
+ }
+ if (_rx_dma != nullptr) {
+ stm32_dmastop(_rx_dma);
+ stm32_dmafree(_rx_dma);
+ }
+
+ /* reset the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* detach our interrupt handler */
+ up_disable_irq(PX4IO_SERIAL_VECTOR);
+ irq_detach(PX4IO_SERIAL_VECTOR);
+
+ /* restore the GPIOs */
+ stm32_unconfiggpio(PX4IO_SERIAL_TX_GPIO);
+ stm32_unconfiggpio(PX4IO_SERIAL_RX_GPIO);
+
+ /* and kill our semaphores */
+ sem_destroy(&_completion_semaphore);
+ sem_destroy(&_bus_semaphore);
+
+ perf_free(_pc_txns);
+ perf_free(_pc_dmasetup);
+ perf_free(_pc_retries);
+ perf_free(_pc_timeouts);
+ perf_free(_pc_crcerrs);
+ perf_free(_pc_dmaerrs);
+ perf_free(_pc_protoerrs);
+ perf_free(_pc_uerrs);
+ perf_free(_pc_idle);
+ perf_free(_pc_badidle);
+
+ if (g_interface == this)
+ g_interface = nullptr;
+}
+
+int
+PX4IO_serial::init()
+{
+ /* allocate DMA */
+ _tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP);
+ _rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP);
+ if ((_tx_dma == nullptr) || (_rx_dma == nullptr))
+ return -1;
+
+ /* configure pins for serial use */
+ stm32_configgpio(PX4IO_SERIAL_TX_GPIO);
+ stm32_configgpio(PX4IO_SERIAL_RX_GPIO);
+
+ /* reset & configure the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* eat any existing interrupt status */
+ (void)rSR;
+ (void)rDR;
+
+ /* configure line speed */
+ uint32_t usartdiv32 = PX4IO_SERIAL_CLOCK / (PX4IO_SERIAL_BITRATE / 2);
+ uint32_t mantissa = usartdiv32 >> 5;
+ uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
+
+ /* attach serial interrupt handler */
+ irq_attach(PX4IO_SERIAL_VECTOR, _interrupt);
+ up_enable_irq(PX4IO_SERIAL_VECTOR);
+
+ /* enable UART in DMA mode, enable error and line idle interrupts */
+ rCR3 = USART_CR3_EIE;
+
+ rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
+
+ /* create semaphores */
+ sem_init(&_completion_semaphore, 0, 0);
+ sem_init(&_bus_semaphore, 0, 1);
+
+
+ /* XXX this could try talking to IO */
+
+ return 0;
+}
+
+int
+PX4IO_serial::ioctl(unsigned operation, unsigned &arg)
+{
+
+ switch (operation) {
+
+ case 1: /* XXX magic number - test operation */
+ switch (arg) {
+ case 0:
+ lowsyslog("test 0\n");
+
+ /* kill DMA, this is a PIO test */
+ stm32_dmastop(_tx_dma);
+ stm32_dmastop(_rx_dma);
+ rCR3 &= ~(USART_CR3_DMAR | USART_CR3_DMAT);
+
+ for (;;) {
+ while (!(rSR & USART_SR_TXE))
+ ;
+ rDR = 0x55;
+ }
+ return 0;
+
+ case 1:
+ {
+ unsigned fails = 0;
+ for (unsigned count = 0;; count++) {
+ uint16_t value = count & 0xffff;
+
+ if (write((PX4IO_PAGE_TEST << 8) | PX4IO_P_TEST_LED, &value, 1) != 0)
+ fails++;
+
+ if (count >= 5000) {
+ lowsyslog("==== test 1 : %u failures ====\n", fails);
+ perf_print_counter(_pc_txns);
+ perf_print_counter(_pc_dmasetup);
+ perf_print_counter(_pc_retries);
+ perf_print_counter(_pc_timeouts);
+ perf_print_counter(_pc_crcerrs);
+ perf_print_counter(_pc_dmaerrs);
+ perf_print_counter(_pc_protoerrs);
+ perf_print_counter(_pc_uerrs);
+ perf_print_counter(_pc_idle);
+ perf_print_counter(_pc_badidle);
+ count = 0;
+ }
+ }
+ return 0;
+ }
+ case 2:
+ lowsyslog("test 2\n");
+ return 0;
+ }
+ default:
+ break;
+ }
+
+ return -1;
+}
+
+int
+PX4IO_serial::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ if (count > PKT_MAX_REGS)
+ return -EINVAL;
+
+ sem_wait(&_bus_semaphore);
+
+ int result;
+ for (unsigned retries = 0; retries < 3; retries++) {
+
+ _dma_buffer.count_code = count | PKT_CODE_WRITE;
+ _dma_buffer.page = page;
+ _dma_buffer.offset = offset;
+ memcpy((void *)&_dma_buffer.regs[0], (void *)values, (2 * count));
+ for (unsigned i = count; i < PKT_MAX_REGS; i++)
+ _dma_buffer.regs[i] = 0x55aa;
+
+ /* XXX implement check byte */
+
+ /* start the transaction and wait for it to complete */
+ result = _wait_complete();
+
+ /* successful transaction? */
+ if (result == OK) {
+
+ /* check result in packet */
+ if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
+
+ /* IO didn't like it - no point retrying */
+ result = -EINVAL;
+ perf_count(_pc_protoerrs);
+ }
+
+ break;
+ }
+ perf_count(_pc_retries);
+ }
+
+ sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
+ return result;
+}
+
+int
+PX4IO_serial::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ uint16_t *values = reinterpret_cast<uint16_t *>(data);
+
+ if (count > PKT_MAX_REGS)
+ return -EINVAL;
+
+ sem_wait(&_bus_semaphore);
+
+ int result;
+ for (unsigned retries = 0; retries < 3; retries++) {
+
+ _dma_buffer.count_code = count | PKT_CODE_READ;
+ _dma_buffer.page = page;
+ _dma_buffer.offset = offset;
+
+ /* start the transaction and wait for it to complete */
+ result = _wait_complete();
+
+ /* successful transaction? */
+ if (result == OK) {
+
+ /* check result in packet */
+ if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
+
+ /* IO didn't like it - no point retrying */
+ result = -EINVAL;
+ perf_count(_pc_protoerrs);
+
+ /* compare the received count with the expected count */
+ } else if (PKT_COUNT(_dma_buffer) != count) {
+
+ /* IO returned the wrong number of registers - no point retrying */
+ result = -EIO;
+ perf_count(_pc_protoerrs);
+
+ /* successful read */
+ } else {
+
+ /* copy back the result */
+ memcpy(values, &_dma_buffer.regs[0], (2 * count));
+ }
+
+ break;
+ }
+ perf_count(_pc_retries);
+ }
+
+ sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
+ return result;
+}
+
+int
+PX4IO_serial::_wait_complete()
+{
+ /* clear any lingering error status */
+ (void)rSR;
+ (void)rDR;
+
+ /* start RX DMA */
+ perf_begin(_pc_txns);
+ perf_begin(_pc_dmasetup);
+
+ /* DMA setup time ~3µs */
+ _rx_dma_status = _dma_status_waiting;
+
+ /*
+ * Note that we enable circular buffer mode as a workaround for
+ * there being no API to disable the DMA FIFO. We need direct mode
+ * because otherwise when the line idle interrupt fires there
+ * will be packet bytes still in the DMA FIFO, and we will assume
+ * that the idle was spurious.
+ *
+ * XXX this should be fixed with a NuttX change.
+ */
+ stm32_dmasetup(
+ _rx_dma,
+ PX4IO_SERIAL_BASE + STM32_USART_DR_OFFSET,
+ reinterpret_cast<uint32_t>(&_dma_buffer),
+ sizeof(_dma_buffer),
+ DMA_SCR_CIRC | /* XXX see note above */
+ DMA_SCR_DIR_P2M |
+ DMA_SCR_MINC |
+ DMA_SCR_PSIZE_8BITS |
+ DMA_SCR_MSIZE_8BITS |
+ DMA_SCR_PBURST_SINGLE |
+ DMA_SCR_MBURST_SINGLE);
+ stm32_dmastart(_rx_dma, _dma_callback, this, false);
+ rCR3 |= USART_CR3_DMAR;
+
+ /* start TX DMA - no callback if we also expect a reply */
+ /* DMA setup time ~3µs */
+ _dma_buffer.crc = 0;
+ _dma_buffer.crc = crc_packet(&_dma_buffer);
+ stm32_dmasetup(
+ _tx_dma,
+ PX4IO_SERIAL_BASE + STM32_USART_DR_OFFSET,
+ reinterpret_cast<uint32_t>(&_dma_buffer),
+ PKT_SIZE(_dma_buffer),
+ DMA_SCR_DIR_M2P |
+ DMA_SCR_MINC |
+ DMA_SCR_PSIZE_8BITS |
+ DMA_SCR_MSIZE_8BITS |
+ DMA_SCR_PBURST_SINGLE |
+ DMA_SCR_MBURST_SINGLE);
+ stm32_dmastart(_tx_dma, nullptr, nullptr, false);
+ //rCR1 &= ~USART_CR1_TE;
+ //rCR1 |= USART_CR1_TE;
+ rCR3 |= USART_CR3_DMAT;
+
+ perf_end(_pc_dmasetup);
+
+ /* compute the deadline for a 10ms timeout */
+ struct timespec abstime;
+ clock_gettime(CLOCK_REALTIME, &abstime);
+ abstime.tv_nsec += 10*1000*1000;
+ if (abstime.tv_nsec >= 1000*1000*1000) {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000*1000*1000;
+ }
+
+ /* wait for the transaction to complete - 64 bytes @ 1.5Mbps ~426µs */
+ int ret;
+ for (;;) {
+ ret = sem_timedwait(&_completion_semaphore, &abstime);
+
+ if (ret == OK) {
+ /* check for DMA errors */
+ if (_rx_dma_status & DMA_STATUS_TEIF) {
+ perf_count(_pc_dmaerrs);
+ ret = -EIO;
+ break;
+ }
+
+ /* check packet CRC - corrupt packet errors mean IO receive CRC error */
+ uint8_t crc = _dma_buffer.crc;
+ _dma_buffer.crc = 0;
+ if ((crc != crc_packet(&_dma_buffer)) | (PKT_CODE(_dma_buffer) == PKT_CODE_CORRUPT)) {
+ perf_count(_pc_crcerrs);
+ ret = -EIO;
+ break;
+ }
+
+ /* successful txn (may still be reporting an error) */
+ break;
+ }
+
+ if (errno == ETIMEDOUT) {
+ /* something has broken - clear out any partial DMA state and reconfigure */
+ _abort_dma();
+ perf_count(_pc_timeouts);
+ perf_cancel(_pc_txns); /* don't count this as a transaction */
+ break;
+ }
+
+ /* we might? see this for EINTR */
+ lowsyslog("unexpected ret %d/%d\n", ret, errno);
+ }
+
+ /* reset DMA status */
+ _rx_dma_status = _dma_status_inactive;
+
+ /* update counters */
+ perf_end(_pc_txns);
+
+ return ret;
+}
+
+void
+PX4IO_serial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
+{
+ if (arg != nullptr) {
+ PX4IO_serial *ps = reinterpret_cast<PX4IO_serial *>(arg);
+
+ ps->_do_rx_dma_callback(status);
+ }
+}
+
+void
+PX4IO_serial::_do_rx_dma_callback(unsigned status)
+{
+ /* on completion of a reply, wake the waiter */
+ if (_rx_dma_status == _dma_status_waiting) {
+
+ /* check for packet overrun - this will occur after DMA completes */
+ uint32_t sr = rSR;
+ if (sr & (USART_SR_ORE | USART_SR_RXNE)) {
+ (void)rDR;
+ status = DMA_STATUS_TEIF;
+ }
+
+ /* save RX status */
+ _rx_dma_status = status;
+
+ /* disable UART DMA */
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+
+ /* complete now */
+ sem_post(&_completion_semaphore);
+ }
+}
+
+int
+PX4IO_serial::_interrupt(int irq, void *context)
+{
+ if (g_interface != nullptr)
+ g_interface->_do_interrupt();
+ return 0;
+}
+
+void
+PX4IO_serial::_do_interrupt()
+{
+ uint32_t sr = rSR; /* get UART status register */
+ (void)rDR; /* read DR to clear status */
+
+ if (sr & (USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
+ USART_SR_NE | /* noise error - we have lost a byte due to noise */
+ USART_SR_FE)) { /* framing error - start/stop bit lost or line break */
+
+ /*
+ * If we are in the process of listening for something, these are all fatal;
+ * abort the DMA with an error.
+ */
+ if (_rx_dma_status == _dma_status_waiting) {
+ _abort_dma();
+
+ perf_count(_pc_uerrs);
+ /* complete DMA as though in error */
+ _do_rx_dma_callback(DMA_STATUS_TEIF);
+
+ return;
+ }
+
+ /* XXX we might want to use FE / line break as an out-of-band handshake ... handle it here */
+
+ /* don't attempt to handle IDLE if it's set - things went bad */
+ return;
+ }
+
+ if (sr & USART_SR_IDLE) {
+
+ /* if there is DMA reception going on, this is a short packet */
+ if (_rx_dma_status == _dma_status_waiting) {
+
+ /* verify that the received packet is complete */
+ unsigned length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
+ perf_count(_pc_badidle);
+
+ /* stop the receive DMA */
+ stm32_dmastop(_rx_dma);
+
+ /* complete the short reception */
+ _do_rx_dma_callback(DMA_STATUS_TEIF);
+ return;
+ }
+
+ perf_count(_pc_idle);
+
+ /* stop the receive DMA */
+ stm32_dmastop(_rx_dma);
+
+ /* complete the short reception */
+ _do_rx_dma_callback(DMA_STATUS_TCIF);
+ }
+ }
+}
+
+void
+PX4IO_serial::_abort_dma()
+{
+ /* disable UART DMA */
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+ (void)rSR;
+ (void)rDR;
+ (void)rDR;
+
+ /* stop DMA */
+ stm32_dmastop(_tx_dma);
+ stm32_dmastop(_rx_dma);
+}
+
+#endif /* PX4IO_SERIAL_BASE */
diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 15524c3ae..dd8abbac5 100644
--- a/src/drivers/px4io/uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -49,53 +49,18 @@
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
+#include <termios.h>
#include <sys/stat.h>
+#include <nuttx/arch.h>
+
+#include <crc32.h>
#include "uploader.h"
-static const uint32_t crctab[] =
-{
- 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
- 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
- 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
- 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
- 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
- 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
- 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
- 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
- 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
- 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
- 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
- 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
- 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
- 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
- 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
- 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
- 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
- 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
- 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
- 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
- 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
- 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
- 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
- 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
- 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
- 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
- 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
- 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
- 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
- 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
- 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
- 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
-};
-
-static uint32_t
-crc32(const uint8_t *src, unsigned len, unsigned state)
-{
- for (unsigned i = 0; i < len; i++)
- state = crctab[(state ^ src[i]) & 0xff] ^ (state >> 8);
- return state;
-}
+#include <board_config.h>
+
+// define for comms logging
+//#define UDEBUG
PX4IO_Uploader::PX4IO_Uploader() :
_io_fd(-1),
@@ -114,24 +79,11 @@ PX4IO_Uploader::upload(const char *filenames[])
const char *filename = NULL;
size_t fw_size;
- _io_fd = open("/dev/ttyS2", O_RDWR);
-
- if (_io_fd < 0) {
- log("could not open interface");
- return -errno;
- }
-
- /* look for the bootloader */
- ret = sync();
-
- if (ret != OK) {
- /* this is immediately fatal */
- log("bootloader not responding");
- close(_io_fd);
- _io_fd = -1;
- return -EIO;
- }
+#ifndef PX4IO_SERIAL_DEVICE
+#error Must define PX4IO_SERIAL_DEVICE in board configuration to support firmware upload
+#endif
+ /* allow an early abort and look for file first */
for (unsigned i = 0; filenames[i] != nullptr; i++) {
_fw_fd = open(filenames[i], O_RDONLY);
@@ -152,9 +104,46 @@ PX4IO_Uploader::upload(const char *filenames[])
return -ENOENT;
}
+ _io_fd = open(PX4IO_SERIAL_DEVICE, O_RDWR);
+
+ if (_io_fd < 0) {
+ log("could not open interface");
+ return -errno;
+ }
+
+ /* save initial uart configuration to reset after the update */
+ struct termios t_original;
+ tcgetattr(_io_fd, &t_original);
+
+ /* adjust line speed to match bootloader */
+ struct termios t;
+ tcgetattr(_io_fd, &t);
+ cfsetspeed(&t, 115200);
+ tcsetattr(_io_fd, TCSANOW, &t);
+
+ /* look for the bootloader for 150 ms */
+ for (int i = 0; i < 15; i++) {
+ ret = sync();
+ if (ret == OK) {
+ break;
+ } else {
+ usleep(10000);
+ }
+ }
+
+ if (ret != OK) {
+ /* this is immediately fatal */
+ log("bootloader not responding");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
+ close(_io_fd);
+ _io_fd = -1;
+ return -EIO;
+ }
+
struct stat st;
if (stat(filename, &st) != 0) {
log("Failed to stat %s - %d\n", filename, (int)errno);
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -errno;
@@ -162,6 +151,7 @@ PX4IO_Uploader::upload(const char *filenames[])
fw_size = st.st_size;
if (_fw_fd == -1) {
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -ENOENT;
@@ -176,6 +166,7 @@ PX4IO_Uploader::upload(const char *filenames[])
if (ret != OK) {
/* this is immediately fatal */
log("bootloader not responding");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -EIO;
@@ -189,6 +180,7 @@ PX4IO_Uploader::upload(const char *filenames[])
log("found bootloader revision: %d", bl_rev);
} else {
log("found unsupported bootloader revision %d, exiting", bl_rev);
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return OK;
@@ -224,6 +216,9 @@ PX4IO_Uploader::upload(const char *filenames[])
if (ret != OK) {
log("reboot failed");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
+ close(_io_fd);
+ _io_fd = -1;
return ret;
}
@@ -233,9 +228,17 @@ PX4IO_Uploader::upload(const char *filenames[])
break;
}
+ /* reset uart to previous/default baudrate */
+ tcsetattr(_io_fd, TCSANOW, &t_original);
+
close(_fw_fd);
close(_io_fd);
_io_fd = -1;
+
+ // sleep for enough time for the IO chip to boot. This makes
+ // forceupdate more reliably startup IO again after update
+ up_udelay(100*1000);
+
return ret;
}
@@ -247,16 +250,20 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
fds[0].fd = _io_fd;
fds[0].events = POLLIN;
- /* wait 100 ms for a character */
+ /* wait <timout> ms for a character */
int ret = ::poll(&fds[0], 1, timeout);
if (ret < 1) {
+#ifdef UDEBUG
log("poll timeout %d", ret);
+#endif
return -ETIMEDOUT;
}
read(_io_fd, &c, 1);
- //log("recv 0x%02x", c);
+#ifdef UDEBUG
+ log("recv 0x%02x", c);
+#endif
return OK;
}
@@ -280,18 +287,25 @@ PX4IO_Uploader::drain()
int ret;
do {
- ret = recv(c, 1000);
+ // the small recv timeout here is to allow for fast
+ // drain when rebooting the io board for a forced
+ // update of the fw without using the safety switch
+ ret = recv(c, 40);
+#ifdef UDEBUG
if (ret == OK) {
- //log("discard 0x%02x", c);
+ log("discard 0x%02x", c);
}
+#endif
} while (ret == OK);
}
int
PX4IO_Uploader::send(uint8_t c)
{
- //log("send 0x%02x", c);
+#ifdef UDEBUG
+ log("send 0x%02x", c);
+#endif
if (write(_io_fd, &c, 1) != 1)
return -errno;
@@ -565,14 +579,14 @@ PX4IO_Uploader::verify_rev3(size_t fw_size_local)
return -errno;
/* calculate crc32 sum */
- sum = crc32((uint8_t *)&file_buf, sizeof(file_buf), sum);
+ sum = crc32part((uint8_t *)&file_buf, sizeof(file_buf), sum);
bytes_read += count;
}
/* fill the rest with 0xff */
while (bytes_read < fw_size_remote) {
- sum = crc32(&fill_blank, sizeof(fill_blank), sum);
+ sum = crc32part(&fill_blank, sizeof(fill_blank), sum);
bytes_read += sizeof(fill_blank);
}
diff --git a/src/drivers/px4io/uploader.h b/src/drivers/px4io/uploader.h
index 135202dd1..55f63eef9 100644
--- a/src/drivers/px4io/uploader.h
+++ b/src/drivers/px4io/uploader.h
@@ -69,7 +69,7 @@ private:
PROTO_REBOOT = 0x30,
INFO_BL_REV = 1, /**< bootloader protocol revision */
- BL_REV = 3, /**< supported bootloader protocol */
+ BL_REV = 4, /**< supported bootloader protocol */
INFO_BOARD_ID = 2, /**< board type */
INFO_BOARD_REV = 3, /**< board revision */
INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */
@@ -91,7 +91,7 @@ private:
void drain();
int send(uint8_t c);
int send(uint8_t *p, unsigned count);
- int get_sync(unsigned timeout = 1000);
+ int get_sync(unsigned timeout = 40);
int sync();
int get_info(int param, uint32_t &val);
int erase();
diff --git a/src/drivers/rgbled/module.mk b/src/drivers/rgbled/module.mk
new file mode 100644
index 000000000..39b53ec9e
--- /dev/null
+++ b/src/drivers/rgbled/module.mk
@@ -0,0 +1,6 @@
+#
+# TCA62724FMG driver for RGB LED
+#
+
+MODULE_COMMAND = rgbled
+SRCS = rgbled.cpp
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
new file mode 100644
index 000000000..4f58891ed
--- /dev/null
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -0,0 +1,713 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Julian Oes <joes@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
+ *
+ * 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 rgbled.cpp
+ *
+ * Driver for the onboard RGB LED controller (TCA62724FMG) connected via I2C.
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include <nuttx/wqueue.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <board_config.h>
+
+#include <drivers/drv_rgbled.h>
+
+#define RGBLED_ONTIME 120
+#define RGBLED_OFFTIME 120
+
+#define ADDR PX4_I2C_OBDEV_LED /**< I2C adress of TCA62724FMG */
+#define SUB_ADDR_START 0x01 /**< write everything (with auto-increment) */
+#define SUB_ADDR_PWM0 0x81 /**< blue (without auto-increment) */
+#define SUB_ADDR_PWM1 0x82 /**< green (without auto-increment) */
+#define SUB_ADDR_PWM2 0x83 /**< red (without auto-increment) */
+#define SUB_ADDR_SETTINGS 0x84 /**< settings (without auto-increment)*/
+
+#define SETTING_NOT_POWERSAVE 0x01 /**< power-save mode not off */
+#define SETTING_ENABLE 0x02 /**< on */
+
+
+class RGBLED : public device::I2C
+{
+public:
+ RGBLED(int bus, int rgbled);
+ virtual ~RGBLED();
+
+
+ virtual int init();
+ virtual int probe();
+ virtual int info();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+private:
+ work_s _work;
+
+ rgbled_mode_t _mode;
+ rgbled_pattern_t _pattern;
+
+ uint8_t _r;
+ uint8_t _g;
+ uint8_t _b;
+ float _brightness;
+
+ bool _running;
+ int _led_interval;
+ bool _should_run;
+ int _counter;
+
+ void set_color(rgbled_color_t ledcolor);
+ void set_mode(rgbled_mode_t mode);
+ void set_pattern(rgbled_pattern_t *pattern);
+
+ static void led_trampoline(void *arg);
+ void led();
+
+ int send_led_enable(bool enable);
+ int send_led_rgb();
+ int get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b);
+};
+
+/* for now, we only support one RGBLED */
+namespace
+{
+RGBLED *g_rgbled;
+}
+
+void rgbled_usage();
+
+extern "C" __EXPORT int rgbled_main(int argc, char *argv[]);
+
+RGBLED::RGBLED(int bus, int rgbled) :
+ I2C("rgbled", RGBLED_DEVICE_PATH, bus, rgbled, 100000),
+ _mode(RGBLED_MODE_OFF),
+ _r(0),
+ _g(0),
+ _b(0),
+ _brightness(1.0f),
+ _running(false),
+ _led_interval(0),
+ _should_run(false),
+ _counter(0)
+{
+ memset(&_work, 0, sizeof(_work));
+ memset(&_pattern, 0, sizeof(_pattern));
+}
+
+RGBLED::~RGBLED()
+{
+}
+
+int
+RGBLED::init()
+{
+ int ret;
+ ret = I2C::init();
+
+ if (ret != OK) {
+ return ret;
+ }
+
+ /* switch off LED on start */
+ send_led_enable(false);
+ send_led_rgb();
+
+ return OK;
+}
+
+int
+RGBLED::probe()
+{
+ int ret;
+ bool on, powersave;
+ uint8_t r, g, b;
+
+ /**
+ this may look strange, but is needed. There is a serial
+ EEPROM (Microchip-24aa01) on the PX4FMU-v1 that responds to
+ a bunch of I2C addresses, including the 0x55 used by this
+ LED device. So we need to do enough operations to be sure
+ we are talking to the right device. These 3 operations seem
+ to be enough, as the 3rd one consistently fails if no
+ RGBLED is on the bus.
+ */
+ if ((ret=get(on, powersave, r, g, b)) != OK ||
+ (ret=send_led_enable(false) != OK) ||
+ (ret=send_led_enable(false) != OK)) {
+ return ret;
+ }
+
+ return ret;
+}
+
+int
+RGBLED::info()
+{
+ int ret;
+ bool on, powersave;
+ uint8_t r, g, b;
+
+ ret = get(on, powersave, r, g, b);
+
+ if (ret == OK) {
+ /* we don't care about power-save mode */
+ log("state: %s", on ? "ON" : "OFF");
+ log("red: %u, green: %u, blue: %u", (unsigned)r, (unsigned)g, (unsigned)b);
+
+ } else {
+ warnx("failed to read led");
+ }
+
+ return ret;
+}
+
+int
+RGBLED::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = ENOTTY;
+
+ switch (cmd) {
+ case RGBLED_SET_RGB:
+ /* set the specified color */
+ _r = ((rgbled_rgbset_t *) arg)->red;
+ _g = ((rgbled_rgbset_t *) arg)->green;
+ _b = ((rgbled_rgbset_t *) arg)->blue;
+ send_led_rgb();
+ return OK;
+
+ case RGBLED_SET_COLOR:
+ /* set the specified color name */
+ set_color((rgbled_color_t)arg);
+ send_led_rgb();
+ return OK;
+
+ case RGBLED_SET_MODE:
+ /* set the specified mode */
+ set_mode((rgbled_mode_t)arg);
+ return OK;
+
+ case RGBLED_SET_PATTERN:
+ /* set a special pattern */
+ set_pattern((rgbled_pattern_t *)arg);
+ return OK;
+
+ default:
+ break;
+ }
+
+ return ret;
+}
+
+
+void
+RGBLED::led_trampoline(void *arg)
+{
+ RGBLED *rgbl = reinterpret_cast<RGBLED *>(arg);
+
+ rgbl->led();
+}
+
+/**
+ * Main loop function
+ */
+void
+RGBLED::led()
+{
+ if (!_should_run) {
+ _running = false;
+ return;
+ }
+
+ switch (_mode) {
+ case RGBLED_MODE_BLINK_SLOW:
+ case RGBLED_MODE_BLINK_NORMAL:
+ case RGBLED_MODE_BLINK_FAST:
+ if (_counter >= 2)
+ _counter = 0;
+
+ send_led_enable(_counter == 0);
+
+ break;
+
+ case RGBLED_MODE_BREATHE:
+
+ if (_counter >= 62)
+ _counter = 0;
+
+ int n;
+
+ if (_counter < 32) {
+ n = _counter;
+
+ } else {
+ n = 62 - _counter;
+ }
+
+ _brightness = n * n / (31.0f * 31.0f);
+ send_led_rgb();
+ break;
+
+ case RGBLED_MODE_PATTERN:
+
+ /* don't run out of the pattern array and stop if the next frame is 0 */
+ if (_counter >= RGBLED_PATTERN_LENGTH || _pattern.duration[_counter] <= 0)
+ _counter = 0;
+
+ set_color(_pattern.color[_counter]);
+ send_led_rgb();
+ _led_interval = _pattern.duration[_counter];
+ break;
+
+ default:
+ break;
+ }
+
+ _counter++;
+
+ /* re-queue ourselves to run again later */
+ work_queue(LPWORK, &_work, (worker_t)&RGBLED::led_trampoline, this, _led_interval);
+}
+
+/**
+ * Parse color constant and set _r _g _b values
+ */
+void
+RGBLED::set_color(rgbled_color_t color)
+{
+ switch (color) {
+ case RGBLED_COLOR_OFF:
+ _r = 0;
+ _g = 0;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_RED:
+ _r = 255;
+ _g = 0;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_YELLOW:
+ _r = 255;
+ _g = 200;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_PURPLE:
+ _r = 255;
+ _g = 0;
+ _b = 255;
+ break;
+
+ case RGBLED_COLOR_GREEN:
+ _r = 0;
+ _g = 255;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_BLUE:
+ _r = 0;
+ _g = 0;
+ _b = 255;
+ break;
+
+ case RGBLED_COLOR_WHITE:
+ _r = 255;
+ _g = 255;
+ _b = 255;
+ break;
+
+ case RGBLED_COLOR_AMBER:
+ _r = 255;
+ _g = 80;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_DIM_RED:
+ _r = 90;
+ _g = 0;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_DIM_YELLOW:
+ _r = 80;
+ _g = 30;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_DIM_PURPLE:
+ _r = 45;
+ _g = 0;
+ _b = 45;
+ break;
+
+ case RGBLED_COLOR_DIM_GREEN:
+ _r = 0;
+ _g = 90;
+ _b = 0;
+ break;
+
+ case RGBLED_COLOR_DIM_BLUE:
+ _r = 0;
+ _g = 0;
+ _b = 90;
+ break;
+
+ case RGBLED_COLOR_DIM_WHITE:
+ _r = 30;
+ _g = 30;
+ _b = 30;
+ break;
+
+ case RGBLED_COLOR_DIM_AMBER:
+ _r = 80;
+ _g = 20;
+ _b = 0;
+ break;
+
+ default:
+ warnx("color unknown");
+ break;
+ }
+}
+
+/**
+ * Set mode, if mode not changed has no any effect (doesn't reset blinks phase)
+ */
+void
+RGBLED::set_mode(rgbled_mode_t mode)
+{
+ if (mode != _mode) {
+ _mode = mode;
+
+ switch (mode) {
+ case RGBLED_MODE_OFF:
+ _should_run = false;
+ send_led_enable(false);
+ break;
+
+ case RGBLED_MODE_ON:
+ _brightness = 1.0f;
+ send_led_rgb();
+ send_led_enable(true);
+ break;
+
+ case RGBLED_MODE_BLINK_SLOW:
+ _should_run = true;
+ _counter = 0;
+ _led_interval = 2000;
+ _brightness = 1.0f;
+ send_led_rgb();
+ break;
+
+ case RGBLED_MODE_BLINK_NORMAL:
+ _should_run = true;
+ _counter = 0;
+ _led_interval = 500;
+ _brightness = 1.0f;
+ send_led_rgb();
+ break;
+
+ case RGBLED_MODE_BLINK_FAST:
+ _should_run = true;
+ _counter = 0;
+ _led_interval = 100;
+ _brightness = 1.0f;
+ send_led_rgb();
+ break;
+
+ case RGBLED_MODE_BREATHE:
+ _should_run = true;
+ _counter = 0;
+ _led_interval = 25;
+ send_led_enable(true);
+ break;
+
+ case RGBLED_MODE_PATTERN:
+ _should_run = true;
+ _counter = 0;
+ _brightness = 1.0f;
+ send_led_enable(true);
+ break;
+
+ default:
+ warnx("mode unknown");
+ break;
+ }
+
+ /* if it should run now, start the workq */
+ if (_should_run && !_running) {
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&RGBLED::led_trampoline, this, 1);
+ }
+
+ }
+}
+
+/**
+ * Set pattern for PATTERN mode, but don't change current mode
+ */
+void
+RGBLED::set_pattern(rgbled_pattern_t *pattern)
+{
+ memcpy(&_pattern, pattern, sizeof(rgbled_pattern_t));
+}
+
+/**
+ * Sent ENABLE flag to LED driver
+ */
+int
+RGBLED::send_led_enable(bool enable)
+{
+ uint8_t settings_byte = 0;
+
+ if (enable)
+ settings_byte |= SETTING_ENABLE;
+
+ settings_byte |= SETTING_NOT_POWERSAVE;
+
+ const uint8_t msg[2] = { SUB_ADDR_SETTINGS, settings_byte};
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+/**
+ * Send RGB PWM settings to LED driver according to current color and brightness
+ */
+int
+RGBLED::send_led_rgb()
+{
+ /* To scale from 0..255 -> 0..15 shift right by 4 bits */
+ const uint8_t msg[6] = {
+ SUB_ADDR_PWM0, (uint8_t)((int)(_b * _brightness) >> 4),
+ SUB_ADDR_PWM1, (uint8_t)((int)(_g * _brightness) >> 4),
+ SUB_ADDR_PWM2, (uint8_t)((int)(_r * _brightness) >> 4)
+ };
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+RGBLED::get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b)
+{
+ uint8_t result[2];
+ int ret;
+
+ ret = transfer(nullptr, 0, &result[0], 2);
+
+ if (ret == OK) {
+ on = result[0] & SETTING_ENABLE;
+ powersave = !(result[0] & SETTING_NOT_POWERSAVE);
+ /* XXX check, looks wrong */
+ r = (result[0] & 0x0f) << 4;
+ g = (result[1] & 0xf0);
+ b = (result[1] & 0x0f) << 4;
+ }
+
+ return ret;
+}
+
+void
+rgbled_usage()
+{
+ warnx("missing command: try 'start', 'test', 'info', 'off', 'stop', 'rgb 30 40 50'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
+ warnx(" -a addr (0x%x)", ADDR);
+}
+
+int
+rgbled_main(int argc, char *argv[])
+{
+ int i2cdevice = -1;
+ int rgbledadr = ADDR; /* 7bit */
+
+ int ch;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ rgbledadr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ rgbled_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ rgbled_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ int fd;
+ int ret;
+
+ if (!strcmp(verb, "start")) {
+ if (g_rgbled != nullptr)
+ errx(1, "already started");
+
+ if (i2cdevice == -1) {
+ // try the external bus first
+ i2cdevice = PX4_I2C_BUS_EXPANSION;
+ g_rgbled = new RGBLED(PX4_I2C_BUS_EXPANSION, rgbledadr);
+
+ if (g_rgbled != nullptr && OK != g_rgbled->init()) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ }
+
+ if (g_rgbled == nullptr) {
+ // fall back to default bus
+ if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
+ errx(1, "init failed");
+ }
+ i2cdevice = PX4_I2C_BUS_LED;
+ }
+ }
+
+ if (g_rgbled == nullptr) {
+ g_rgbled = new RGBLED(i2cdevice, rgbledadr);
+
+ if (g_rgbled == nullptr)
+ errx(1, "new failed");
+
+ if (OK != g_rgbled->init()) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ errx(1, "init failed");
+ }
+ }
+
+ exit(0);
+ }
+
+ /* need the driver past this point */
+ if (g_rgbled == nullptr) {
+ warnx("not started");
+ rgbled_usage();
+ exit(1);
+ }
+
+ if (!strcmp(verb, "test")) {
+ fd = open(RGBLED_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+
+ rgbled_pattern_t pattern = { {RGBLED_COLOR_RED, RGBLED_COLOR_GREEN, RGBLED_COLOR_BLUE, RGBLED_COLOR_WHITE, RGBLED_COLOR_OFF, RGBLED_COLOR_OFF},
+ {500, 500, 500, 500, 1000, 0 } // "0" indicates end of pattern
+ };
+
+ ret = ioctl(fd, RGBLED_SET_PATTERN, (unsigned long)&pattern);
+ ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_PATTERN);
+
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "info")) {
+ g_rgbled->info();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "off") || !strcmp(verb, "stop")) {
+ fd = open(RGBLED_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_OFF);
+ close(fd);
+ 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>");
+ }
+
+ fd = open(RGBLED_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+
+ rgbled_rgbset_t v;
+ v.red = strtol(argv[2], NULL, 0);
+ v.green = strtol(argv[3], NULL, 0);
+ v.blue = strtol(argv[4], NULL, 0);
+ ret = ioctl(fd, RGBLED_SET_RGB, (unsigned long)&v);
+ ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_ON);
+ close(fd);
+ exit(ret);
+ }
+
+ rgbled_usage();
+ exit(0);
+}
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
new file mode 100644
index 000000000..d65a9be36
--- /dev/null
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -0,0 +1,328 @@
+/****************************************************************************
+ *
+ * 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 RoboClaw.cpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#include "RoboClaw.hpp"
+#include <poll.h>
+#include <stdio.h>
+#include <math.h>
+#include <string.h>
+#include <fcntl.h>
+#include <termios.h>
+
+#include <systemlib/err.h>
+#include <arch/board/board.h>
+#include <mavlink/mavlink_log.h>
+
+#include <controllib/uorb/UOrbPublication.hpp>
+#include <uORB/topics/debug_key_value.h>
+#include <drivers/drv_hrt.h>
+
+uint8_t RoboClaw::checksum_mask = 0x7f;
+
+RoboClaw::RoboClaw(const char *deviceName, uint16_t address,
+ uint16_t pulsesPerRev):
+ _address(address),
+ _pulsesPerRev(pulsesPerRev),
+ _uart(0),
+ _controlPoll(),
+ _actuators(NULL, ORB_ID(actuator_controls_0), 20),
+ _motor1Position(0),
+ _motor1Speed(0),
+ _motor1Overflow(0),
+ _motor2Position(0),
+ _motor2Speed(0),
+ _motor2Overflow(0)
+{
+ // setup control polling
+ _controlPoll.fd = _actuators.getHandle();
+ _controlPoll.events = POLLIN;
+
+ // start serial port
+ _uart = open(deviceName, O_RDWR | O_NOCTTY);
+ if (_uart < 0) err(1, "could not open %s", deviceName);
+ int ret = 0;
+ struct termios uart_config;
+ ret = tcgetattr(_uart, &uart_config);
+ if (ret < 0) err (1, "failed to get attr");
+ uart_config.c_oflag &= ~ONLCR; // no CR for every LF
+ ret = cfsetispeed(&uart_config, B38400);
+ if (ret < 0) err (1, "failed to set input speed");
+ ret = cfsetospeed(&uart_config, B38400);
+ if (ret < 0) err (1, "failed to set output speed");
+ ret = tcsetattr(_uart, TCSANOW, &uart_config);
+ if (ret < 0) err (1, "failed to set attr");
+
+ // setup default settings, reset encoders
+ resetEncoders();
+}
+
+RoboClaw::~RoboClaw()
+{
+ setMotorDutyCycle(MOTOR_1, 0.0);
+ setMotorDutyCycle(MOTOR_2, 0.0);
+ close(_uart);
+}
+
+int RoboClaw::readEncoder(e_motor motor)
+{
+ uint16_t sum = 0;
+ if (motor == MOTOR_1) {
+ _sendCommand(CMD_READ_ENCODER_1, nullptr, 0, sum);
+ } else if (motor == MOTOR_2) {
+ _sendCommand(CMD_READ_ENCODER_2, nullptr, 0, sum);
+ }
+ uint8_t rbuf[50];
+ usleep(5000);
+ int nread = read(_uart, rbuf, 50);
+ if (nread < 6) {
+ printf("failed to read\n");
+ return -1;
+ }
+ //printf("received: \n");
+ //for (int i=0;i<nread;i++) {
+ //printf("%d\t", rbuf[i]);
+ //}
+ //printf("\n");
+ uint32_t count = 0;
+ uint8_t * countBytes = (uint8_t *)(&count);
+ countBytes[3] = rbuf[0];
+ countBytes[2] = rbuf[1];
+ countBytes[1] = rbuf[2];
+ countBytes[0] = rbuf[3];
+ uint8_t status = rbuf[4];
+ uint8_t checksum = rbuf[5];
+ uint8_t checksum_computed = (sum + _sumBytes(rbuf, 5)) &
+ checksum_mask;
+ // check if checksum is valid
+ if (checksum != checksum_computed) {
+ printf("checksum failed: expected %d got %d\n",
+ checksum, checksum_computed);
+ return -1;
+ }
+ int overFlow = 0;
+
+ if (status & STATUS_REVERSE) {
+ //printf("roboclaw: reverse\n");
+ }
+
+ if (status & STATUS_UNDERFLOW) {
+ //printf("roboclaw: underflow\n");
+ overFlow = -1;
+ } else if (status & STATUS_OVERFLOW) {
+ //printf("roboclaw: overflow\n");
+ overFlow = +1;
+ }
+
+ static int64_t overflowAmount = 0x100000000LL;
+ if (motor == MOTOR_1) {
+ _motor1Overflow += overFlow;
+ _motor1Position = float(int64_t(count) +
+ _motor1Overflow*overflowAmount)/_pulsesPerRev;
+ } else if (motor == MOTOR_2) {
+ _motor2Overflow += overFlow;
+ _motor2Position = float(int64_t(count) +
+ _motor2Overflow*overflowAmount)/_pulsesPerRev;
+ }
+ return 0;
+}
+
+void RoboClaw::printStatus(char *string, size_t n)
+{
+ snprintf(string, n,
+ "pos1,spd1,pos2,spd2: %10.2f %10.2f %10.2f %10.2f\n",
+ double(getMotorPosition(MOTOR_1)),
+ double(getMotorSpeed(MOTOR_1)),
+ double(getMotorPosition(MOTOR_2)),
+ double(getMotorSpeed(MOTOR_2)));
+}
+
+float RoboClaw::getMotorPosition(e_motor motor)
+{
+ if (motor == MOTOR_1) {
+ return _motor1Position;
+ } else if (motor == MOTOR_2) {
+ return _motor2Position;
+ }
+}
+
+float RoboClaw::getMotorSpeed(e_motor motor)
+{
+ if (motor == MOTOR_1) {
+ return _motor1Speed;
+ } else if (motor == MOTOR_2) {
+ return _motor2Speed;
+ }
+}
+
+int RoboClaw::setMotorSpeed(e_motor motor, float value)
+{
+ uint16_t sum = 0;
+ // bound
+ if (value > 1) value = 1;
+ if (value < -1) value = -1;
+ uint8_t speed = fabs(value)*127;
+ // send command
+ if (motor == MOTOR_1) {
+ if (value > 0) {
+ return _sendCommand(CMD_DRIVE_FWD_1, &speed, 1, sum);
+ } else {
+ return _sendCommand(CMD_DRIVE_REV_1, &speed, 1, sum);
+ }
+ } else if (motor == MOTOR_2) {
+ if (value > 0) {
+ return _sendCommand(CMD_DRIVE_FWD_2, &speed, 1, sum);
+ } else {
+ return _sendCommand(CMD_DRIVE_REV_2, &speed, 1, sum);
+ }
+ }
+ return -1;
+}
+
+int RoboClaw::setMotorDutyCycle(e_motor motor, float value)
+{
+ uint16_t sum = 0;
+ // bound
+ if (value > 1) value = 1;
+ if (value < -1) value = -1;
+ int16_t duty = 1500*value;
+ // send command
+ if (motor == MOTOR_1) {
+ return _sendCommand(CMD_SIGNED_DUTYCYCLE_1,
+ (uint8_t *)(&duty), 2, sum);
+ } else if (motor == MOTOR_2) {
+ return _sendCommand(CMD_SIGNED_DUTYCYCLE_2,
+ (uint8_t *)(&duty), 2, sum);
+ }
+ return -1;
+}
+
+int RoboClaw::resetEncoders()
+{
+ uint16_t sum = 0;
+ return _sendCommand(CMD_RESET_ENCODERS,
+ nullptr, 0, sum);
+}
+
+int RoboClaw::update()
+{
+ // wait for an actuator publication,
+ // check for exit condition every second
+ // note "::poll" is required to distinguish global
+ // poll from member function for driver
+ if (::poll(&_controlPoll, 1, 1000) < 0) return -1; // poll error
+
+ // if new data, send to motors
+ if (_actuators.updated()) {
+ _actuators.update();
+ setMotorDutyCycle(MOTOR_1,_actuators.control[CH_VOLTAGE_LEFT]);
+ setMotorDutyCycle(MOTOR_2,_actuators.control[CH_VOLTAGE_RIGHT]);
+ }
+ return 0;
+}
+
+uint16_t RoboClaw::_sumBytes(uint8_t * buf, size_t n)
+{
+ uint16_t sum = 0;
+ //printf("sum\n");
+ for (size_t i=0;i<n;i++) {
+ sum += buf[i];
+ //printf("%d\t", buf[i]);
+ }
+ //printf("total sum %d\n", sum);
+ return sum;
+}
+
+int RoboClaw::_sendCommand(e_command cmd, uint8_t * data,
+ size_t n_data, uint16_t & prev_sum)
+{
+ tcflush(_uart, TCIOFLUSH); // flush buffers
+ uint8_t buf[n_data + 3];
+ buf[0] = _address;
+ buf[1] = cmd;
+ for (size_t i=0;i<n_data;i++) {
+ buf[i+2] = data[n_data - i - 1]; // MSB
+ }
+ uint16_t sum = _sumBytes(buf, n_data + 2);
+ prev_sum += sum;
+ buf[n_data + 2] = sum & checksum_mask;
+ //printf("\nmessage:\n");
+ //for (size_t i=0;i<n_data+3;i++) {
+ //printf("%d\t", buf[i]);
+ //}
+ //printf("\n");
+ return write(_uart, buf, n_data + 3);
+}
+
+int roboclawTest(const char *deviceName, uint8_t address,
+ uint16_t pulsesPerRev)
+{
+ printf("roboclaw test: starting\n");
+
+ // setup
+ RoboClaw roboclaw(deviceName, address, pulsesPerRev);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_1, 0.3);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_2, 0.3);
+ char buf[200];
+ for (int i=0; i<10; i++) {
+ usleep(100000);
+ roboclaw.readEncoder(RoboClaw::MOTOR_1);
+ roboclaw.readEncoder(RoboClaw::MOTOR_2);
+ roboclaw.printStatus(buf,200);
+ printf("%s", buf);
+ }
+
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_1, -0.3);
+ roboclaw.setMotorDutyCycle(RoboClaw::MOTOR_2, -0.3);
+ for (int i=0; i<10; i++) {
+ usleep(100000);
+ roboclaw.readEncoder(RoboClaw::MOTOR_1);
+ roboclaw.readEncoder(RoboClaw::MOTOR_2);
+ roboclaw.printStatus(buf,200);
+ printf("%s", buf);
+ }
+
+ printf("Test complete\n");
+ return 0;
+}
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/roboclaw/RoboClaw.hpp b/src/drivers/roboclaw/RoboClaw.hpp
new file mode 100644
index 000000000..e9f35cf95
--- /dev/null
+++ b/src/drivers/roboclaw/RoboClaw.hpp
@@ -0,0 +1,192 @@
+/****************************************************************************
+ *
+ * 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 RoboClas.hpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#pragma once
+
+#include <poll.h>
+#include <stdio.h>
+#include <controllib/uorb/UOrbSubscription.hpp>
+#include <uORB/topics/actuator_controls.h>
+#include <drivers/device/i2c.h>
+
+/**
+ * This is a driver for the RoboClaw motor controller
+ */
+class RoboClaw
+{
+public:
+
+ /** control channels */
+ enum e_channel {
+ CH_VOLTAGE_LEFT = 0,
+ CH_VOLTAGE_RIGHT
+ };
+
+ /** motors */
+ enum e_motor {
+ MOTOR_1 = 0,
+ MOTOR_2
+ };
+
+ /**
+ * constructor
+ * @param deviceName the name of the
+ * serial port e.g. "/dev/ttyS2"
+ * @param address the adddress of the motor
+ * (selectable on roboclaw)
+ * @param pulsesPerRev # of encoder
+ * pulses per revolution of wheel
+ */
+ RoboClaw(const char *deviceName, uint16_t address,
+ uint16_t pulsesPerRev);
+
+ /**
+ * deconstructor
+ */
+ virtual ~RoboClaw();
+
+ /**
+ * @return position of a motor, rev
+ */
+ float getMotorPosition(e_motor motor);
+
+ /**
+ * @return speed of a motor, rev/sec
+ */
+ float getMotorSpeed(e_motor motor);
+
+ /**
+ * set the speed of a motor, rev/sec
+ */
+ int setMotorSpeed(e_motor motor, float value);
+
+ /**
+ * set the duty cycle of a motor, rev/sec
+ */
+ int setMotorDutyCycle(e_motor motor, float value);
+
+ /**
+ * reset the encoders
+ * @return status
+ */
+ int resetEncoders();
+
+ /**
+ * main update loop that updates RoboClaw motor
+ * dutycycle based on actuator publication
+ */
+ int update();
+
+ /**
+ * read data from serial
+ */
+ int readEncoder(e_motor motor);
+
+ /**
+ * print status
+ */
+ void printStatus(char *string, size_t n);
+
+private:
+
+ // Quadrature status flags
+ enum e_quadrature_status_flags {
+ STATUS_UNDERFLOW = 1 << 0, /**< encoder went below 0 **/
+ STATUS_REVERSE = 1 << 1, /**< motor doing in reverse dir **/
+ STATUS_OVERFLOW = 1 << 2, /**< encoder went above 2^32 **/
+ };
+
+ // commands
+ // We just list the commands we want from the manual here.
+ enum e_command {
+
+ // simple
+ CMD_DRIVE_FWD_1 = 0,
+ CMD_DRIVE_REV_1 = 1,
+ CMD_DRIVE_FWD_2 = 4,
+ CMD_DRIVE_REV_2 = 5,
+
+ // encoder commands
+ CMD_READ_ENCODER_1 = 16,
+ CMD_READ_ENCODER_2 = 17,
+ CMD_RESET_ENCODERS = 20,
+
+ // advanced motor control
+ CMD_READ_SPEED_HIRES_1 = 30,
+ CMD_READ_SPEED_HIRES_2 = 31,
+ CMD_SIGNED_DUTYCYCLE_1 = 32,
+ CMD_SIGNED_DUTYCYCLE_2 = 33,
+ };
+
+ static uint8_t checksum_mask;
+
+ uint16_t _address;
+ uint16_t _pulsesPerRev;
+
+ int _uart;
+
+ /** poll structure for control packets */
+ struct pollfd _controlPoll;
+
+ /** actuator controls subscription */
+ control::UOrbSubscription<actuator_controls_s> _actuators;
+
+ // private data
+ float _motor1Position;
+ float _motor1Speed;
+ int16_t _motor1Overflow;
+
+ float _motor2Position;
+ float _motor2Speed;
+ int16_t _motor2Overflow;
+
+ // private methods
+ uint16_t _sumBytes(uint8_t * buf, size_t n);
+ int _sendCommand(e_command cmd, uint8_t * data, size_t n_data, uint16_t & prev_sum);
+};
+
+// unit testing
+int roboclawTest(const char *deviceName, uint8_t address,
+ uint16_t pulsesPerRev);
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/roboclaw/module.mk b/src/drivers/roboclaw/module.mk
new file mode 100644
index 000000000..1abecf198
--- /dev/null
+++ b/src/drivers/roboclaw/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.
+#
+############################################################################
+
+#
+# RoboClaw Motor Controller
+#
+
+MODULE_COMMAND = roboclaw
+
+SRCS = roboclaw_main.cpp \
+ RoboClaw.cpp
diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp
new file mode 100644
index 000000000..44ed03254
--- /dev/null
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -0,0 +1,195 @@
+/****************************************************************************
+ *
+ * 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 roboclaw_main.cpp
+ *
+ * RoboClaw Motor Driver
+ *
+ * references:
+ * http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
+ *
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <math.h>
+
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+
+#include <arch/board/board.h>
+#include "RoboClaw.hpp"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+
+/**
+ * Deamon management function.
+ */
+extern "C" __EXPORT int roboclaw_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int roboclaw_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage();
+
+static void usage()
+{
+ fprintf(stderr, "usage: roboclaw "
+ "{start|stop|status|test}\n\n");
+}
+
+/**
+ * The deamon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int roboclaw_main(int argc, char *argv[])
+{
+
+ if (argc < 1)
+ usage();
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("roboclaw already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn_cmd("roboclaw",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 10,
+ 2048,
+ roboclaw_thread_main,
+ (const char **)argv);
+ exit(0);
+
+ } else if (!strcmp(argv[1], "test")) {
+
+ const char * deviceName = "/dev/ttyS2";
+ uint8_t address = 128;
+ uint16_t pulsesPerRev = 1200;
+
+ if (argc == 2) {
+ printf("testing with default settings\n");
+ } else if (argc != 4) {
+ printf("usage: roboclaw test device address pulses_per_rev\n");
+ exit(-1);
+ } else {
+ deviceName = argv[2];
+ address = strtoul(argv[3], nullptr, 0);
+ pulsesPerRev = strtoul(argv[4], nullptr, 0);
+ }
+
+ printf("device:\t%s\taddress:\t%d\tpulses per rev:\t%ld\n",
+ deviceName, address, pulsesPerRev);
+
+ roboclawTest(deviceName, address, pulsesPerRev);
+ thread_should_exit = true;
+ exit(0);
+
+ } else if (!strcmp(argv[1], "stop")) {
+
+ thread_should_exit = true;
+ exit(0);
+
+ } else if (!strcmp(argv[1], "status")) {
+
+ if (thread_running) {
+ printf("\troboclaw app is running\n");
+
+ } else {
+ printf("\troboclaw app not started\n");
+ }
+ exit(0);
+ }
+
+ usage();
+ exit(1);
+}
+
+int roboclaw_thread_main(int argc, char *argv[])
+{
+ printf("[roboclaw] starting\n");
+
+ // skip parent process args
+ argc -=2;
+ argv +=2;
+
+ if (argc < 3) {
+ printf("usage: roboclaw start device address\n");
+ return -1;
+ }
+
+ const char *deviceName = argv[1];
+ uint8_t address = strtoul(argv[2], nullptr, 0);
+ uint16_t pulsesPerRev = strtoul(argv[3], nullptr, 0);
+
+ printf("device:\t%s\taddress:\t%d\tpulses per rev:\t%ld\n",
+ deviceName, address, pulsesPerRev);
+
+ // start
+ RoboClaw roboclaw(deviceName, address, pulsesPerRev);
+
+ thread_running = true;
+
+ // loop
+ while (!thread_should_exit) {
+ roboclaw.update();
+ }
+
+ // exit
+ printf("[roboclaw] exiting.\n");
+ thread_running = false;
+ return 0;
+}
+
+// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 1020eb946..00e46d6b8 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -227,7 +227,6 @@ ADC::init()
if ((hrt_absolute_time() - now) > 500) {
log("sample timeout");
return -1;
- return 0xffff;
}
}
@@ -282,7 +281,7 @@ ADC::close_last(struct file *filp)
void
ADC::_tick_trampoline(void *arg)
{
- ((ADC *)arg)->_tick();
+ (reinterpret_cast<ADC *>(arg))->_tick();
}
void
@@ -342,7 +341,7 @@ test(void)
err(1, "can't open ADC device");
for (unsigned i = 0; i < 50; i++) {
- adc_msg_s data[8];
+ adc_msg_s data[10];
ssize_t count = read(fd, data, sizeof(data));
if (count < 0)
@@ -366,8 +365,15 @@ int
adc_main(int argc, char *argv[])
{
if (g_adc == nullptr) {
- /* XXX this hardcodes the default channel set for PX4FMU - should be configurable */
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ /* XXX this hardcodes the default channel set for PX4FMUv1 - should be configurable */
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ /* XXX this hardcodes the default channel set for PX4FMUv2 - should be configurable */
+ g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
+ (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
+#endif
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 05e1cd8ec..b7c9b89a4 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 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
@@ -59,7 +59,7 @@
#include <errno.h>
#include <string.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include "chip.h"
@@ -70,7 +70,7 @@
#include "stm32_gpio.h"
#include "stm32_tim.h"
-#ifdef CONFIG_HRT_TIMER
+#ifdef HRT_TIMER
/* HRT configuration */
#if HRT_TIMER == 1
@@ -155,7 +155,7 @@
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
#else
-# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
+# error HRT_TIMER must be a value between 1 and 11
#endif
/*
@@ -168,7 +168,7 @@
# error HRT_TIMER_CLOCK must be greater than 1MHz
#endif
-/*
+/**
* Minimum/maximum deadlines.
*
* These are suitable for use with a 16-bit timer/counter clocked
@@ -275,11 +275,17 @@ static void hrt_call_invoke(void);
/*
* Specific registers and bits used by PPM sub-functions
*/
-#ifdef CONFIG_HRT_PPM
-/*
+#ifdef HRT_PPM_CHANNEL
+/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
+ *
+ * Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
*/
-# ifndef GTIM_CCER_CC1NP
+# ifdef CONFIG_ARCH_CORTEXM3
+# undef GTIM_CCER_CC1NP
+# undef GTIM_CCER_CC2NP
+# undef GTIM_CCER_CC3NP
+# undef GTIM_CCER_CC4NP
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
@@ -324,20 +330,27 @@ static void hrt_call_invoke(void);
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC4P
# else
-# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
+# error HRT_PPM_CHANNEL must be a value between 1 and 4
# endif
/*
* PPM decoder tuning parameters
*/
-# define PPM_MAX_PULSE_WIDTH 550 /* maximum width of a valid pulse */
-# define PPM_MIN_CHANNEL_VALUE 800 /* shortest valid channel signal */
-# define PPM_MAX_CHANNEL_VALUE 2200 /* longest valid channel signal */
-# define PPM_MIN_START 2500 /* shortest valid start gap */
+# define PPM_MIN_PULSE_WIDTH 200 /**< minimum width of a valid first pulse */
+# define PPM_MAX_PULSE_WIDTH 600 /**< maximum width of a valid first pulse */
+# define PPM_MIN_CHANNEL_VALUE 800 /**< shortest valid channel signal */
+# define PPM_MAX_CHANNEL_VALUE 2200 /**< longest valid channel signal */
+# define PPM_MIN_START 2300 /**< shortest valid start gap (only 2nd part of pulse) */
/* decoded PPM buffer */
-#define PPM_MAX_CHANNELS 12
+#define PPM_MIN_CHANNELS 5
+#define PPM_MAX_CHANNELS 20
+
+/** Number of same-sized frames required to 'lock' */
+#define PPM_CHANNEL_LOCK 4 /**< should be less than the input timeout */
+
__EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS];
+__EXPORT uint16_t ppm_frame_length = 0;
__EXPORT unsigned ppm_decoded_channels = 0;
__EXPORT uint64_t ppm_last_valid_decode = 0;
@@ -351,11 +364,12 @@ unsigned ppm_pulse_next;
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
-/* PPM decoder state machine */
+/** PPM decoder state machine */
struct {
- uint16_t last_edge; /* last capture time */
- uint16_t last_mark; /* last significant edge */
- unsigned next_channel;
+ uint16_t last_edge; /**< last capture time */
+ uint16_t last_mark; /**< last significant edge */
+ uint16_t frame_start; /**< the frame width */
+ unsigned next_channel; /**< next channel index */
enum {
UNSYNCH = 0,
ARM,
@@ -375,9 +389,9 @@ static void hrt_ppm_decode(uint32_t status);
# define CCMR1_PPM 0
# define CCMR2_PPM 0
# define CCER_PPM 0
-#endif /* CONFIG_HRT_PPM */
+#endif /* HRT_PPM_CHANNEL */
-/*
+/**
* Initialise the timer we are going to use.
*
* We expect that we'll own one of the reduced-function STM32 general
@@ -422,8 +436,8 @@ hrt_tim_init(void)
up_enable_irq(HRT_TIMER_VECTOR);
}
-#ifdef CONFIG_HRT_PPM
-/*
+#ifdef HRT_PPM_CHANNEL
+/**
* Handle the PPM decoder state machine.
*/
static void
@@ -438,9 +452,8 @@ hrt_ppm_decode(uint32_t status)
if (status & SR_OVF_PPM)
goto error;
- /* how long since the last edge? */
+ /* how long since the last edge? - this handles counter wrapping implicitely. */
width = count - ppm.last_edge;
- ppm.last_edge = count;
ppm_edge_history[ppm_edge_next++] = width;
@@ -453,14 +466,39 @@ hrt_ppm_decode(uint32_t status)
*/
if (width >= PPM_MIN_START) {
- /* export the last set of samples if we got something sensible */
- if (ppm.next_channel > 4) {
- for (i = 0; i < ppm.next_channel && i < PPM_MAX_CHANNELS; i++)
- ppm_buffer[i] = ppm_temp_buffer[i];
+ /*
+ * If the number of channels changes unexpectedly, we don't want
+ * to just immediately jump on the new count as it may be a result
+ * of noise or dropped edges. Instead, take a few frames to settle.
+ */
+ if (ppm.next_channel != ppm_decoded_channels) {
+ static unsigned new_channel_count;
+ static unsigned new_channel_holdoff;
+
+ if (new_channel_count != ppm.next_channel) {
+ /* start the lock counter for the new channel count */
+ new_channel_count = ppm.next_channel;
+ new_channel_holdoff = PPM_CHANNEL_LOCK;
+
+ } else if (new_channel_holdoff > 0) {
+ /* this frame matched the last one, decrement the lock counter */
+ new_channel_holdoff--;
+
+ } else {
+ /* we have seen PPM_CHANNEL_LOCK frames with the new count, accept it */
+ ppm_decoded_channels = new_channel_count;
+ new_channel_count = 0;
+ }
+
+ } else {
+ /* frame channel count matches expected, let's use it */
+ if (ppm.next_channel > PPM_MIN_CHANNELS) {
+ for (i = 0; i < ppm.next_channel; i++)
+ ppm_buffer[i] = ppm_temp_buffer[i];
- ppm_decoded_channels = i;
- ppm_last_valid_decode = hrt_absolute_time();
+ ppm_last_valid_decode = hrt_absolute_time();
+ }
}
/* reset for the next frame */
@@ -469,29 +507,39 @@ hrt_ppm_decode(uint32_t status)
/* next edge is the reference for the first channel */
ppm.phase = ARM;
+ ppm.last_edge = count;
return;
}
switch (ppm.phase) {
case UNSYNCH:
/* we are waiting for a start pulse - nothing useful to do here */
- return;
+ break;
case ARM:
/* we expect a pulse giving us the first mark */
- if (width > PPM_MAX_PULSE_WIDTH)
- goto error; /* pulse was too long */
+ if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH)
+ goto error; /* pulse was too short or too long */
/* record the mark timing, expect an inactive edge */
- ppm.last_mark = count;
- ppm.phase = INACTIVE;
- return;
+ ppm.last_mark = ppm.last_edge;
+
+ /* frame length is everything including the start gap */
+ ppm_frame_length = (uint16_t)(ppm.last_edge - ppm.frame_start);
+ ppm.frame_start = ppm.last_edge;
+ ppm.phase = ACTIVE;
+ break;
case INACTIVE:
+
+ /* we expect a short pulse */
+ if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH)
+ goto error; /* pulse was too short or too long */
+
/* this edge is not interesting, but now we are ready for the next mark */
ppm.phase = ACTIVE;
- return;
+ break;
case ACTIVE:
/* determine the interval from the last mark */
@@ -512,10 +560,13 @@ hrt_ppm_decode(uint32_t status)
ppm_temp_buffer[ppm.next_channel++] = interval;
ppm.phase = INACTIVE;
- return;
+ break;
}
+ ppm.last_edge = count;
+ return;
+
/* the state machine is corrupted; reset it */
error:
@@ -524,9 +575,9 @@ error:
ppm_decoded_channels = 0;
}
-#endif /* CONFIG_HRT_PPM */
+#endif /* HRT_PPM_CHANNEL */
-/*
+/**
* Handle the compare interupt by calling the callout dispatcher
* and then re-scheduling the next deadline.
*/
@@ -544,7 +595,7 @@ hrt_tim_isr(int irq, void *context)
/* ack the interrupts we just read */
rSR = ~status;
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/* was this a PPM edge? */
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
@@ -555,6 +606,7 @@ hrt_tim_isr(int irq, void *context)
hrt_ppm_decode(status);
}
+
#endif
/* was this a timer tick? */
@@ -573,7 +625,7 @@ hrt_tim_isr(int irq, void *context)
return OK;
}
-/*
+/**
* Fetch a never-wrapping absolute time value in microseconds from
* some arbitrary epoch shortly after system start.
*/
@@ -620,7 +672,7 @@ hrt_absolute_time(void)
return abstime;
}
-/*
+/**
* Convert a timespec to absolute time
*/
hrt_abstime
@@ -634,7 +686,7 @@ ts_to_abstime(struct timespec *ts)
return result;
}
-/*
+/**
* Convert absolute time to a timespec.
*/
void
@@ -645,7 +697,7 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
ts->tv_nsec = abstime * 1000;
}
-/*
+/**
* Compare a time value with the current time.
*/
hrt_abstime
@@ -660,7 +712,7 @@ hrt_elapsed_time(const volatile hrt_abstime *then)
return delta;
}
-/*
+/**
* Store the absolute time in an interrupt-safe fashion
*/
hrt_abstime
@@ -675,7 +727,7 @@ hrt_store_absolute_time(volatile hrt_abstime *now)
return ts;
}
-/*
+/**
* Initalise the high-resolution timing module.
*/
void
@@ -684,13 +736,13 @@ hrt_init(void)
sq_init(&callout_queue);
hrt_tim_init();
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/* configure the PPM input pin */
stm32_configgpio(GPIO_PPM_IN);
#endif
}
-/*
+/**
* Call callout(arg) after interval has elapsed.
*/
void
@@ -703,7 +755,7 @@ hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, v
arg);
}
-/*
+/**
* Call callout(arg) at calltime.
*/
void
@@ -712,7 +764,7 @@ hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, v
hrt_call_internal(entry, calltime, 0, callout, arg);
}
-/*
+/**
* Call callout(arg) every period.
*/
void
@@ -731,6 +783,13 @@ hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime inte
irqstate_t flags = irqsave();
/* if the entry is currently queued, remove it */
+ /* note that we are using a potentially uninitialised
+ entry->link here, but it is safe as sq_rem() doesn't
+ dereference the passed node unless it is found in the
+ list. So we potentially waste a bit of time searching the
+ queue for the uninitialised entry->link but we don't do
+ anything actually unsafe.
+ */
if (entry->deadline != 0)
sq_rem(&entry->link, &callout_queue);
@@ -744,7 +803,7 @@ hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime inte
irqrestore(flags);
}
-/*
+/**
* If this returns true, the call has been invoked and removed from the callout list.
*
* Always returns false for repeating callouts.
@@ -755,7 +814,7 @@ hrt_called(struct hrt_call *entry)
return (entry->deadline == 0);
}
-/*
+/**
* Remove the entry from the callout list.
*/
void
@@ -837,13 +896,19 @@ hrt_call_invoke(void)
/* if the callout has a non-zero period, it has to be re-entered */
if (call->period != 0) {
- call->deadline = deadline + call->period;
+ // re-check call->deadline to allow for
+ // callouts to re-schedule themselves
+ // using hrt_call_delay()
+ if (call->deadline <= now) {
+ call->deadline = deadline + call->period;
+ }
+
hrt_call_enter(call);
}
}
}
-/*
+/**
* Reschedule the next timer interrupt.
*
* This routine must be called with interrupts disabled.
@@ -904,5 +969,16 @@ hrt_latency_update(void)
latency_counters[index]++;
}
+void
+hrt_call_init(struct hrt_call *entry)
+{
+ memset(entry, 0, sizeof(*entry));
+}
+
+void
+hrt_call_delay(struct hrt_call *entry, hrt_abstime delay)
+{
+ entry->deadline = hrt_absolute_time() + delay;
+}
-#endif /* CONFIG_HRT_TIMER */
+#endif /* HRT_TIMER */
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index 7b060412c..dbb45a138 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -88,6 +88,7 @@
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
+#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
static void pwm_timer_init(unsigned timer);
static void pwm_timer_set_rate(unsigned timer, unsigned rate);
@@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer)
rCCER(timer) = 0;
rDCR(timer) = 0;
+ if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) {
+ /* master output enable = on */
+ rBDTR(timer) = ATIM_BDTR_MOE;
+ }
+
/* configure the timer to free-run at 1MHz */
rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1;
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 167ef30a8..f36f2091e 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -104,7 +104,7 @@
#include <math.h>
#include <ctype.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <arch/stm32/chip.h>
@@ -117,10 +117,6 @@
#include <systemlib/err.h>
-#ifndef CONFIG_HRT_TIMER
-# error This driver requires CONFIG_HRT_TIMER
-#endif
-
/* Tone alarm configuration */
#if TONE_ALARM_TIMER == 2
# define TONE_ALARM_BASE STM32_TIM2_BASE
@@ -234,13 +230,18 @@ public:
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual ssize_t write(file *filp, const char *buffer, size_t len);
+ inline const char *name(int tune) {
+ return _tune_names[tune];
+ }
private:
- static const unsigned _tune_max = 1024; // be reasonable about user tunes
- static const char * const _default_tunes[];
- static const unsigned _default_ntunes;
+ static const unsigned _tune_max = 1024 * 8; // be reasonable about user tunes
+ const char * _default_tunes[TONE_NUMBER_OF_TUNES];
+ const char * _tune_names[TONE_NUMBER_OF_TUNES];
static const uint8_t _note_tab[];
+ unsigned _default_tune_number; // number of currently playing default tune (0 for none)
+
const char *_user_tune;
const char *_tune; // current tune string
@@ -306,160 +307,6 @@ private:
};
-// predefined tune array
-const char * const ToneAlarm::_default_tunes[] = {
- "MFT240L8 O4aO5dc O4aO5dc O4aO5dc L16dcdcdcdc", // startup tune
- "MBT200a8a8a8PaaaP", // ERROR tone
- "MFT200e8a8a", // NotifyPositive tone
- "MFT200e8e", // NotifyNeutral tone
- "MFT200e8c8e8c8e8c8", // NotifyNegative tone
- "MFT90O3C16.C32C16.C32C16.C32G16.E32G16.E32G16.E32C16.C32C16.C32C16.C32G16.E32G16.E32G16.E32C4", // charge!
- "MFT60O3C32O2A32F16F16F32G32A32A+32O3C16C16C16O2A16", // dixie
- "MFT90O2C16C16C16F8.A8C16C16C16F8.A4P16P8", // cucuracha
- "MNT150L8O2GGABGBADGGABL4GL8F+", // yankee
- "MFT200O3C4.O2A4.G4.F4.D8E8F8D4F8C2.O2G4.O3C4.O2A4.F4.D8E8F8G4A8G2P8", // daisy
- "T200O2B4P8B16B16B4P8B16B16B8G+8E8G+8B8G+8B8O3E8" // william tell
- "O2B8G+8E8G+8B8G+8B8O3E8O2B4P8B16B16B4P8B16"
- "O2B16B4P8B16B16B4P8B16B16B8B16B16B8B8B8B16"
- "O2B16B8B8B8B16B16B8B8B8B16B16B8B8B2B2B8P8"
- "P4P4P8O1B16B16B8B16B16B8B16B16O2E8F+8G+8"
- "O1B16B16B8B16B16O2E8G+16G+16F+8D+8O1B8B16"
- "O1B16B8B16B16B8B16B16O2E8F+8G+8E16G+16B4"
- "O2B16A16G+16F+16E8G+8E8O3B16B16B8B16B16B8"
- "O3B16B16O4E8F+8G+8O3B16B16B8B16B16O4E8G+16"
- "O4G+16F+8D+8O3B8B16B16B8B16B16B8B16B16O4E8"
- "O4F+8G+8E16G+16B4B16A16G+16F+16E8G+8E8O3G+16"
- "O3G+16G+8G+16G+16G+8G+16G+16G+8O4C+8O3G+8"
- "O4C+8O3G+8O4C+8O3G+8F+8E8D+8C+8G+16G+16G+8"
- "O3G+16G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8O3G+8"
- "O4C+8O3B8A+8B8A+8B8G+16G+16G+8G+16G+16G+8"
- "O3G+16G+16G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3G+8"
- "O3F+8E8D+8C+8G+16G+16G+8G+16G+16G+8G+16G+16"
- "O3G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3B8A+8B8O2B16"
- "O2B16B8F+16F+16F+8F+16F+16F+8G+8A8F+4A8G+8"
- "O2E4G+8F+8F+8F+8O3F+16F+16F+8F+16F+16F+8"
- "O3G+8A8F+4A8G+8E4G+8F+8O2B16B16B8O1B16B16"
- "O1B8B16B16B8B16B16O2E8F+8G+8O1B16B16B8B16"
- "O1B16O2E8G+16G+16F+8D+8O1B8B16B16B8B16B16"
- "O1B8B16B16O2E8F+8G+8E16G+16B4B16A16G+16F+16"
- "O2E8G+8E8O3B16B16B8B16B16B8B16B16O4E8F+8"
- "O4G+8O3B16B16B8B16B16O4E8G+16G+16F+8D+8O3B8"
- "O3B16B16B8B16B16B8B16B16O4E8F+8G+8E16G+16"
- "O4B4B16A16G+16F+16E8G+8E8O3E64F64G64A64B64"
- "O4C64D64E8E16E16E8E8G+4.F+8E8D+8E8C+8O3B16"
- "O4C+16O3B16O4C+16O3B16O4C+16D+16E16O3A16"
- "O3B16A16B16A16B16O4C+16D+16O3G+16A16G+16"
- "O3A16G+16A16B16O4C+16O3F+16G+16F+16G+16F+16"
- "O3G+16F+16G+16F+16G+16F+16D+16O2B16O3B16"
- "O4C+16D+16E8D+8E8C+8O3B16O4C+16O3B16O4C+16"
- "O3B16O4C+16D+16E16O3A16B16A16B16A16B16O4C+16"
- "O4D+16O3G+16A16G+16A16G+16A16B16O4C+16O3F+16"
- "O3G+16F+16G+16F+16A16F+16E16E8P8C+4C+16O2C16"
- "O3C+16O2C16O3D+16C+16O2B16A16A16G+16E16C+16"
- "O2C+16C+16C+16C+16E16D+16O1C16G+16G+16G+16"
- "O1G+16G+16G+16O2C+16E16G+16O3C+16C+16C+16"
- "O3C+16C+16O2C16O3C+16O2C16O3D+16C+16O2B16"
- "O2A16A16G+16E16C+16C+16C+16C+16C+16E16D+16"
- "O1C16G+16G+16G+16G+16G+16G+16O2C+16E16G+16"
- "O3C+16E16D+16C+16D+16O2C16G+16G+16G+16O3G+16"
- "O3E16C+16D+16O2C16G+16G+16G+16O3G+16E16C+16"
- "O3D+16O2B16G+16G+16A+16G16D+16D+16G+16G16"
- "O2G+16G16G+16A16G+16F+16E16O1B16A+16B16O2E16"
- "O1B16O2F+16O1B16O2G+16E16D+16E16G+16E16A16"
- "O2F+16B16O3G+16F+16E16D+16F+16E16C+16O2B16"
- "O3C+16O2B16O3C+16D+16E16F+16G+16O2A16B16"
- "O2A16B16O3C+16D+16E16F+16O2G+16A16G+16A16"
- "O2C16O3C+16D+16E16O2F+16G+16F+16G+16F+16"
- "O2G+16F+16G+16F+16G+16F+16D+16O1B16C16O2C+16"
- "O2D+16E16O1B16A+16B16O2E16O1B16O2F+16O1B16"
- "O2G+16E16D+16E16G+16E16A16F+16B16O3G+16F+16"
- "O3E16D+16F+16E16C+16O2B16O3C+16O2B16O3C+16"
- "O3D+16E16F+16G+16O2A16B16A16B16O3C+16D+16"
- "O3E16F+16O2G+16A16G+16A16B16O3C+16D+16E16"
- "O2F+16O3C+16O2C16O3C+16D+16C+16O2A16F+16"
- "O2E16O3E16F+16G+16A16B16O4C+16D+16E8E16E16"
- "O4E8E8G+4.F8E8D+8E8C+8O3B16O4C+16O3B16O4C+16"
- "O3B16O4C+16D+16E16O3A16B16A16B16A16B16O4C+16"
- "O4D+16O3G+16A16G+16A16G+16A16B16O4C+16O3F+16"
- "O3G+16F+16G+16F+16G+16F+16G+16F+16G+16F+16"
- "O3D+16O2B16O3B16O4C+16D+16E8E16E16E8E8G+4."
- "O4F+8E8D+8E8C+8O3B16O4C+16O3B16O4C+16O3B16"
- "O4C+16D+16E16O3A16B16A16B16A16B16O4C+16D+16"
- "O3G+16A16G+16A16G+16A16B16O4C+16O3F+16G+16"
- "O3F+16G+16F+16A16G+16F+16E8O2B8O3E8G+16G+16"
- "O3G+8G+16G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8"
- "O3G+8O4C+8O3G+8F+8E8D+8C+8G+16G+16G+8G+16"
- "O3G+16G+8G+16G+16G+8O4C+8O3G+8O4C+8O3G+8"
- "O4C+8O3B8A+8B8A+8B8G+16G+16G+8G+16G+16G+8"
- "O3G+16G+16G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3G+8"
- "O3F+8E8D+8C+8G+16G+16G+8G+16G+16G+8G+16G+16"
- "O3G+8O4C+8O3G+8O4C+8O3G+8O4C+8O3B8A+8B8A+8"
- "O3B8O2F+16F+16F+8F+16F+16F+8G+8A8F+4A8G+8"
- "O2E4G+8F+8B8O1B8O2F+16F+16F+8F+16F+16F+8"
- "O2G+8A8F+4A8G+8E4G+8F+8B16B16B8O1B16B16B8"
- "O1B16B16B8B16B16O2E8F+8G+8O1B16B16B8B16B16"
- "O2E8G+16G+16F+8D+8O1B8B16B16B8B16B16B8B16"
- "O1B16O2E8F+8G+8E16G+16B4B16A16G+16F+16E8"
- "O1B8O2E8O3B16B16B8B16B16B8B16B16O4E8F+8G+8"
- "O3B16B16B8B16B16O4E8G+16G+16F+8D+8O3B8B16"
- "O3B16B8B16B16B8B16B16O4E8F+8G+8O3E16G+16"
- "O3B4B16A16G+16F+16E16F+16G+16A16G+16A16B16"
- "O4C+16O3B16O4C+16D+16E16D+16E16F+16G+16A16"
- "O3B16O4A16O3B16O4A16O3B16O4A16O3B16O4A16"
- "O3B16O4A16O3B16O4A16O3B16O4A16O3B16E16F+16"
- "O3G+16A16G+16A16B16O4C+16O3B16O4C+16D+16"
- "O4E16D+16E16F+16G+16A16O3B16O4A16O3B16O4A16"
- "O3B16O4A16O3B16O4A16O3B16O4A16O3B16O4A16"
- "O3B16O4A16O3B16P16G+16O4G+16O3G+16P16D+16"
- "O4D+16O3D+16P16E16O4E16O3E16P16A16O4A16O3A16"
- "P16O3G+16O4G+16O3G+16P16D+16O4D+16O3D+16"
- "P16O3E16O4E16O3E16P16A16O4A16O3A16O4G16O3G16"
- "O4G16O3G16O4G16O3G16O4G16O3G16O4G8E8C8E8"
- "O4G+16O3G+16O4G+16O3G+16O4G+16O3G+16O4G+16"
- "O3G+16O4G+8E8O3B8O4E8G+16O3G+16O4G+16O3G+16"
- "O4G+16O3G+16O4G+16O3G+16O4G+8F8C+8F8A+16"
- "O3A+16O4A+16O3A+16O4A+16O3A+16O4A+16O3A+16"
- "O4A+8G8E8G8B8P16A+16P16A16P16G+16P16F+16"
- "P16O4E16P16D+16P16C+16P16O3B16P16A+16P16"
- "O3A16P16G+16P16F+16P16E16P16D+16P16F+16E16"
- "O3F+16G+16A16G+16A16B16O4C+16O3B16O4C+16"
- "O4D+16E16D+16E16F+16G+16A16O3B16O4A16O3B16"
- "O4A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16"
- "O4A16O3B16O4A16O3B16E16F+16G+16A16G+16A16"
- "O3B16O4C+16O3B16O4C+16D+16E16D+16E16F+16"
- "O4G+16A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16"
- "O4A16O3B16O4A16O3B16O4A16O3B16O4A16O3B16"
- "P16O3G+16O4G+16O3G+16P16D+16O4D+16O3D+16"
- "P16O3E16O4E16O3E16P16A16O4A16O3A16P16G+16"
- "O4G+16O3G+16P16D+16O4D+16O3D+16P16E16O4E16"
- "O3E16P16A16O4A16O3A16O4G16O3G16O4G16O3G16"
- "O4G16O3G16O4G16O3G16O4G8E8C8E8G+16O3G+16"
- "O4G+16O3G+16O4G+16O3G+16O4G+16O3G+16O4G+8"
- "O4E8O3B8O4E8G+16O3G+16O4G+16O3G+16O4G+16"
- "O3G+16O4G+16O3G+16O4G+8F8C+8F8A+16O3A+16"
- "O4A+16O3A+16O4A+16O3A+16O4A+16O3A+16O4A+8"
- "O4G8E8G8B8P16A+16P16A16P16G+16P16F+16P16"
- "O4E16P16D+16P16C+16P16O3B16P16A+16P16A16"
- "P16O3G+16P16F+16P16E16P16D+16P16F16E16D+16"
- "O3E16D+16E8B16B16B8B16B16B8B16B16O4E8F+8"
- "O4G+8O3B16B16B8B16B16B8B16B16O4G+8A8B8P8"
- "O4E8F+8G+8P8O3G+8A8B8P8P2O2B16C16O3C+16D16"
- "O3D+16E16F16F+16G16G+16A16A+16B16C16O4C+16"
- "O4D+16E16D+16F+16D+16E16D+16F+16D+16E16D+16"
- "O4F+16D+16E16D+16F+16D+16E16D+16F+16D+16"
- "O4E16D+16F+16D+16E16D+16F+16D+16E16D+16F+16"
- "O4D+16E8E16O3E16O4E16O3E16O4E16O3E16O4E8"
- "O3B16O2B16O3B16O2B16O3B16O2B16O3B8G+16O2G+16"
- "O3G+16O2G+16O3G+16O2G+16O3G8E16O2E16O3E16"
- "O2E16O3E16O2E16O3E8E16E16E8E8E8O2B16B16B8"
- "O2B8B8G+16G+16G+8G+8G+8E16E16E8E8E8O1B8O2E8"
- "O1B8O2G+8E8B8G+8O3E8O2B8O3E8O2B8O3G+8E8B8"
- "O3G+8O4E4P8E16E16E8E8E8E8E4P8E16E4P8O2E16"
- "O2E2P64",
-};
-
-const unsigned ToneAlarm::_default_ntunes = sizeof(_default_tunes) / sizeof(_default_tunes[0]);
-
// semitone offsets from C for the characters 'A'-'G'
const uint8_t ToneAlarm::_note_tab[] = {9, 11, 0, 2, 4, 5, 7};
@@ -470,13 +317,33 @@ extern "C" __EXPORT int tone_alarm_main(int argc, char *argv[]);
ToneAlarm::ToneAlarm() :
- CDev("tone_alarm", "/dev/tone_alarm"),
+ CDev("tone_alarm", TONEALARM_DEVICE_PATH),
+ _default_tune_number(0),
_user_tune(nullptr),
_tune(nullptr),
_next(nullptr)
{
// enable debug() calls
//_debug_enabled = true;
+ _default_tunes[TONE_STARTUP_TUNE] = "MFT240L8 O4aO5dc O4aO5dc O4aO5dc L16dcdcdcdc"; // startup tune
+ _default_tunes[TONE_ERROR_TUNE] = "MBT200a8a8a8PaaaP"; // ERROR tone
+ _default_tunes[TONE_NOTIFY_POSITIVE_TUNE] = "MFT200e8a8a"; // Notify Positive tone
+ _default_tunes[TONE_NOTIFY_NEUTRAL_TUNE] = "MFT200e8e"; // Notify Neutral tone
+ _default_tunes[TONE_NOTIFY_NEGATIVE_TUNE] = "MFT200e8c8e8c8e8c8"; // Notify Negative tone
+ _default_tunes[TONE_ARMING_WARNING_TUNE] = "MNT75L1O2G"; //arming warning
+ _default_tunes[TONE_BATTERY_WARNING_SLOW_TUNE] = "MBNT100a8"; //battery warning slow
+ _default_tunes[TONE_BATTERY_WARNING_FAST_TUNE] = "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"; //battery warning fast
+ _default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow
+
+ _tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
+ _tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
+ _tune_names[TONE_NOTIFY_POSITIVE_TUNE] = "positive"; // Notify Positive tone
+ _tune_names[TONE_NOTIFY_NEUTRAL_TUNE] = "neutral"; // Notify Neutral tone
+ _tune_names[TONE_NOTIFY_NEGATIVE_TUNE] = "negative"; // Notify Negative tone
+ _tune_names[TONE_ARMING_WARNING_TUNE] = "arming"; // arming warning
+ _tune_names[TONE_BATTERY_WARNING_SLOW_TUNE] = "slow_bat"; // battery warning slow
+ _tune_names[TONE_BATTERY_WARNING_FAST_TUNE] = "fast_bat"; // battery warning fast
+ _tune_names[TONE_GPS_WARNING_TUNE] = "gps_warning"; // gps warning
}
ToneAlarm::~ToneAlarm()
@@ -803,8 +670,12 @@ tune_error:
// stop (and potentially restart) the tune
tune_end:
stop_note();
- if (_repeat)
+ if (_repeat) {
start_tune(_tune);
+ } else {
+ _tune = nullptr;
+ _default_tune_number = 0;
+ }
return;
}
@@ -867,14 +738,20 @@ ToneAlarm::ioctl(file *filp, int cmd, unsigned long arg)
case TONE_SET_ALARM:
debug("TONE_SET_ALARM %u", arg);
- if (arg <= _default_ntunes) {
- if (arg == 0) {
+ if (arg < TONE_NUMBER_OF_TUNES) {
+ if (arg == TONE_STOP_TUNE) {
// stop the tune
_tune = nullptr;
_next = nullptr;
+ _repeat = false;
+ _default_tune_number = 0;
} else {
- // play the selected tune
- start_tune(_default_tunes[arg - 1]);
+ /* always interrupt alarms, unless they are repeating and already playing */
+ if (!(_repeat && _default_tune_number == arg)) {
+ /* play the selected tune */
+ _default_tune_number = arg;
+ start_tune(_default_tunes[arg]);
+ }
}
} else {
result = -EINVAL;
@@ -945,10 +822,10 @@ play_tune(unsigned tune)
{
int fd, ret;
- fd = open("/dev/tone_alarm", 0);
+ fd = open(TONEALARM_DEVICE_PATH, 0);
if (fd < 0)
- err(1, "/dev/tone_alarm");
+ err(1, TONEALARM_DEVICE_PATH);
ret = ioctl(fd, TONE_SET_ALARM, tune);
close(fd);
@@ -960,18 +837,21 @@ play_tune(unsigned tune)
}
int
-play_string(const char *str)
+play_string(const char *str, bool free_buffer)
{
int fd, ret;
- fd = open("/dev/tone_alarm", O_WRONLY);
+ fd = open(TONEALARM_DEVICE_PATH, O_WRONLY);
if (fd < 0)
- err(1, "/dev/tone_alarm");
+ err(1, TONEALARM_DEVICE_PATH);
ret = write(fd, str, strlen(str) + 1);
close(fd);
+ if (free_buffer)
+ free((void *)str);
+
if (ret < 0)
err(1, "play tune");
exit(0);
@@ -997,22 +877,50 @@ tone_alarm_main(int argc, char *argv[])
}
}
- if ((argc > 1) && !strcmp(argv[1], "start"))
- play_tune(1);
-
- if ((argc > 1) && !strcmp(argv[1], "stop"))
- play_tune(0);
-
- if ((tune = strtol(argv[1], nullptr, 10)) != 0)
- play_tune(tune);
+ if (argc > 1) {
+ const char *argv1 = argv[1];
+
+ if (!strcmp(argv1, "start"))
+ play_tune(TONE_STARTUP_TUNE);
+
+ if (!strcmp(argv1, "stop"))
+ play_tune(TONE_STOP_TUNE);
+
+ if ((tune = strtol(argv1, nullptr, 10)) != 0)
+ play_tune(tune);
+
+ /* It might be a tune name */
+ for (tune = 1; tune < TONE_NUMBER_OF_TUNES; tune++)
+ if (!strcmp(g_dev->name(tune), argv1))
+ play_tune(tune);
+
+ /* If it is a file name then load and play it as a string */
+ if (*argv1 == '/') {
+ FILE *fd = fopen(argv1, "r");
+ int sz;
+ char *buffer;
+ if (fd == nullptr)
+ errx(1, "couldn't open '%s'", argv1);
+ fseek(fd, 0, SEEK_END);
+ sz = ftell(fd);
+ fseek(fd, 0, SEEK_SET);
+ buffer = (char *)malloc(sz + 1);
+ if (buffer == nullptr)
+ errx(1, "not enough memory memory");
+ fread(buffer, sz, 1, fd);
+ /* terminate the string */
+ buffer[sz] = 0;
+ play_string(buffer, true);
+ }
- /* if it looks like a PLAY string... */
- if (strlen(argv[1]) > 2) {
- const char *str = argv[1];
- if (str[0] == 'M') {
- play_string(str);
+ /* if it looks like a PLAY string... */
+ if (strlen(argv1) > 2) {
+ if (*argv1 == 'M') {
+ play_string(argv1, false);
+ }
}
+
}
- errx(1, "unrecognised command, try 'start', 'stop' or an alarm number");
+ errx(1, "unrecognized command, try 'start', 'stop', an alarm number or name, or a file name starting with a '/'");
}