aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_defaults4
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk12
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig2
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig4
-rw-r--r--src/drivers/batt_smbus/batt_smbus.cpp540
-rw-r--r--src/drivers/batt_smbus/module.mk8
-rw-r--r--src/drivers/device/i2c.h2
-rw-r--r--src/drivers/drv_batt_smbus.h47
-rw-r--r--src/drivers/drv_px4flow.h2
-rw-r--r--src/drivers/drv_sensor.h15
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp245
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp3
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp361
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp490
-rw-r--r--src/drivers/px4flow/px4flow.cpp33
-rw-r--r--src/modules/commander/commander.cpp23
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp63
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp9
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk4
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp39
-rw-r--r--src/modules/navigator/navigator_params.c8
-rw-r--r--src/modules/navigator/rtl_params.c11
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h2
-rw-r--r--src/modules/sensors/sensor_params.c19
-rw-r--r--src/modules/sensors/sensors.cpp32
-rw-r--r--src/modules/uORB/topics/vehicle_status.h6
-rw-r--r--src/modules/uORB/topics/vtol_vehicle_status.h1
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp21
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_params.c23
30 files changed, 1625 insertions, 406 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index fab2a7f18..e6de64054 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -10,7 +10,7 @@ then
param set NAV_LAND_ALT 90
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
- param set NAV_ACCEPT_RAD 50
+ param set NAV_ACC_RAD 50
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
index 307a64c4d..24d9650a0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults
@@ -41,7 +41,9 @@ then
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
- param set NAV_ACCEPT_RAD 2.0
+ param set NAV_ACC_RAD 2.0
+ param set RTL_RETURN_ALT 30.0
+ param set RTL_DESCEND_ALT 10.0
fi
set PWM_RATE 400
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index 7119c723b..d7e48f03b 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -109,10 +109,10 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
- -funsafe-math-optimizations \
- -fno-builtin-printf \
- -ffunction-sections \
- -fdata-sections
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
# enable precise stack overflow tracking
# note - requires corresponding support in NuttX
@@ -228,7 +228,7 @@ DEP_INCLUDES = $(subst .o,.d,$(OBJS))
define COMPILE
@$(ECHO) "CC: $1"
@$(MKDIR) -p $(dir $2)
- $(Q) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
+ $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
endef
# Compile C++ source $1 to $2
@@ -237,7 +237,7 @@ endef
define COMPILEXX
@$(ECHO) "CXX: $1"
@$(MKDIR) -p $(dir $2)
- $(Q) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
+ $(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
endef
# Assemble $1 into $2
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index edf49b26e..fade1f0c6 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -404,7 +404,7 @@ CONFIG_SIG_SIGWORK=4
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=38
+CONFIG_NFILE_DESCRIPTORS=42
CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index e31f40cd2..50d5b0296 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -323,7 +323,7 @@ CONFIG_STM32_USART_SINGLEWIRE=y
#
# CONFIG_STM32_I2C_DYNTIMEO is not set
CONFIG_STM32_I2CTIMEOSEC=0
-CONFIG_STM32_I2CTIMEOMS=1
+CONFIG_STM32_I2CTIMEOMS=10
# CONFIG_STM32_I2C_DUTY16_9 is not set
#
@@ -438,7 +438,7 @@ CONFIG_SIG_SIGWORK=4
CONFIG_MAX_TASKS=32
CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=38
+CONFIG_NFILE_DESCRIPTORS=42
CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_PREALLOC_MQ_MSGS=4
diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
new file mode 100644
index 000000000..dd83dacaf
--- /dev/null
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -0,0 +1,540 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Randy Mackay <rmackay9@yahoo.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 batt_smbus.cpp
+ *
+ * Driver for a battery monitor connected via SMBus (I2C).
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <sched.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 <ctype.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <board_config.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/subsystem_info.h>
+#include <uORB/topics/battery_status.h>
+
+#include <float.h>
+
+#include <drivers/device/i2c.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_batt_smbus.h>
+#include <drivers/device/ringbuffer.h>
+
+#define BATT_SMBUS_ADDR_MIN 0x08 /* lowest possible address */
+#define BATT_SMBUS_ADDR_MAX 0x7F /* highest possible address */
+
+#define BATT_SMBUS_I2C_BUS PX4_I2C_BUS_EXPANSION
+#define BATT_SMBUS_ADDR 0x0B /* I2C address */
+#define BATT_SMBUS_TEMP 0x08 /* temperature register */
+#define BATT_SMBUS_VOLTAGE 0x09 /* voltage register */
+#define BATT_SMBUS_DESIGN_CAPACITY 0x18 /* design capacity register */
+#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 /* design voltage register */
+#define BATT_SMBUS_SERIALNUM 0x1c /* serial number register */
+#define BATT_SMBUS_MANUFACTURE_NAME 0x20 /* manufacturer name */
+#define BATT_SMBUS_MANUFACTURE_INFO 0x25 /* cell voltage register */
+#define BATT_SMBUS_CURRENT 0x2a /* current register */
+#define BATT_SMBUS_MEASUREMENT_INTERVAL_MS (1000000 / 10) /* time in microseconds, measure at 10hz */
+
+#define BATT_SMBUS_PEC_POLYNOMIAL 0x07 /* Polynomial for calculating PEC */
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class BATT_SMBUS : public device::I2C
+{
+public:
+ BATT_SMBUS(int bus = PX4_I2C_BUS_EXPANSION, uint16_t batt_smbus_addr = BATT_SMBUS_ADDR);
+ virtual ~BATT_SMBUS();
+
+ virtual int init();
+ virtual int test();
+ int search(); /* search all possible slave addresses for a smart battery */
+
+protected:
+ virtual int probe(); // check if the device can be contacted
+
+private:
+
+ // start periodic reads from the battery
+ void start();
+
+ // stop periodic reads from the battery
+ void stop();
+
+ // static function that is called by worker queue
+ static void cycle_trampoline(void *arg);
+
+ // perform a read from the battery
+ void cycle();
+
+ // read_reg - read a word from specified register
+ int read_reg(uint8_t reg, uint16_t &val);
+
+ // read_block - returns number of characters read if successful, zero if unsuccessful
+ uint8_t read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero);
+
+ // get_PEC - calculate PEC for a read or write from the battery
+ // buff is the data that was read or will be written
+ uint8_t get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
+
+ // internal variables
+ work_s _work; // work queue for scheduling reads
+ RingBuffer *_reports; // buffer of recorded voltages, currents
+ struct battery_status_s _last_report; // last published report, used for test()
+ orb_advert_t _batt_topic;
+ orb_id_t _batt_orb_id;
+};
+
+/* for now, we only support one BATT_SMBUS */
+namespace
+{
+BATT_SMBUS *g_batt_smbus;
+}
+
+void batt_smbus_usage();
+
+extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);
+
+// constructor
+BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
+ I2C("batt_smbus", BATT_SMBUS_DEVICE_PATH, bus, batt_smbus_addr, 400000),
+ _work{},
+ _reports(nullptr),
+ _batt_topic(-1),
+ _batt_orb_id(nullptr)
+{
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+// destructor
+BATT_SMBUS::~BATT_SMBUS()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+}
+
+int
+BATT_SMBUS::init()
+{
+ int ret = ENOTTY;
+
+ // attempt to initialise I2C bus
+ ret = I2C::init();
+
+ if (ret != OK) {
+ errx(1,"failed to init I2C");
+ return ret;
+ } else {
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(struct battery_status_s));
+ if (_reports == nullptr) {
+ ret = ENOTTY;
+ } else {
+ // start work queue
+ start();
+ }
+ }
+
+ // init orb id
+ _batt_orb_id = ORB_ID(battery_status);
+
+ return ret;
+}
+
+int
+BATT_SMBUS::test()
+{
+ int sub = orb_subscribe(ORB_ID(battery_status));
+ bool updated = false;
+ struct battery_status_s status;
+ uint64_t start_time = hrt_absolute_time();
+
+ // loop for 5 seconds
+ while ((hrt_absolute_time() - start_time) < 5000000) {
+
+ // display new info that has arrived from the orb
+ orb_check(sub, &updated);
+ if (updated) {
+ if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
+ warnx("V=%4.2f C=%4.2f", status.voltage_v, status.current_a);
+ }
+ }
+
+ // sleep for 0.05 seconds
+ usleep(50000);
+ }
+
+ return OK;
+}
+
+/* search all possible slave addresses for a smart battery */
+int
+BATT_SMBUS::search()
+{
+ bool found_slave = false;
+ uint16_t tmp;
+
+ // search through all valid SMBus addresses
+ for (uint8_t i=BATT_SMBUS_ADDR_MIN; i<=BATT_SMBUS_ADDR_MAX; i++) {
+ set_address(i);
+ if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
+ warnx("battery found at 0x%x",(int)i);
+ found_slave = true;
+ }
+ // short sleep
+ usleep(1);
+ }
+
+ // display completion message
+ if (found_slave) {
+ warnx("Done.");
+ } else {
+ warnx("No smart batteries found.");
+ }
+
+ return OK;
+}
+
+int
+BATT_SMBUS::probe()
+{
+ // always return OK to ensure device starts
+ return OK;
+}
+
+// start periodic reads from the battery
+void
+BATT_SMBUS::start()
+{
+ /* reset the report ring and state machine */
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&BATT_SMBUS::cycle_trampoline, this, 1);
+}
+
+// stop periodic reads from the battery
+void
+BATT_SMBUS::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+// static function that is called by worker queue
+void
+BATT_SMBUS::cycle_trampoline(void *arg)
+{
+ BATT_SMBUS *dev = (BATT_SMBUS *)arg;
+
+ dev->cycle();
+}
+
+// perform a read from the battery
+void
+BATT_SMBUS::cycle()
+{
+ // read data from sensor
+ struct battery_status_s new_report;
+
+ // set time of reading
+ new_report.timestamp = hrt_absolute_time();
+
+ // read voltage
+ uint16_t tmp;
+ if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
+ // initialise new_report
+ memset(&new_report, 0, sizeof(new_report));
+
+ // convert millivolts to volts
+ new_report.voltage_v = ((float)tmp) / 1000.0f;
+
+ // read current
+ usleep(1);
+ uint8_t buff[4];
+ if (read_block(BATT_SMBUS_CURRENT, buff, 4, false) == 4) {
+ new_report.current_a = (float)((int32_t)((uint32_t)buff[3]<<24 | (uint32_t)buff[2]<<16 | (uint32_t)buff[1]<<8 | (uint32_t)buff[0])) / 1000.0f;
+ }
+
+ // publish to orb
+ if (_batt_topic != -1) {
+ orb_publish(_batt_orb_id, _batt_topic, &new_report);
+ } else {
+ _batt_topic = orb_advertise(_batt_orb_id, &new_report);
+ if (_batt_topic < 0) {
+ errx(1, "ADVERT FAIL");
+ }
+ }
+
+ // copy report for test()
+ _last_report = new_report;
+
+ /* post a report to the ring */
+ _reports->force(&new_report);
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+ }
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK, &_work, (worker_t)&BATT_SMBUS::cycle_trampoline, this, USEC2TICK(BATT_SMBUS_MEASUREMENT_INTERVAL_MS));
+}
+
+int
+BATT_SMBUS::read_reg(uint8_t reg, uint16_t &val)
+{
+ uint8_t buff[3]; // 2 bytes of data + PEC
+
+ // read from register
+ int ret = transfer(&reg, 1, buff, 3);
+ if (ret == OK) {
+ // check PEC
+ uint8_t pec = get_PEC(reg, true, buff, 2);
+ if (pec == buff[2]) {
+ val = (uint16_t)buff[1] << 8 | (uint16_t)buff[0];
+ } else {
+ ret = ENOTTY;
+ }
+ }
+
+ // return success or failure
+ return ret;
+}
+
+// read_block - returns number of characters read if successful, zero if unsuccessful
+uint8_t BATT_SMBUS::read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero)
+{
+ uint8_t buff[max_len+2]; // buffer to hold results
+
+ usleep(1);
+
+ // read bytes including PEC
+ int ret = transfer(&reg, 1, buff, max_len+2);
+
+ // return zero on failure
+ if (ret != OK) {
+ return 0;
+ }
+
+ // get length
+ uint8_t bufflen = buff[0];
+
+ // sanity check length returned by smbus
+ if (bufflen == 0 || bufflen > max_len) {
+ return 0;
+ }
+
+ // check PEC
+ uint8_t pec = get_PEC(reg, true, buff, bufflen+1);
+ if (pec != buff[bufflen+1]) {
+ // debug
+ warnx("CurrPEC:%x vs MyPec:%x",(int)buff[bufflen+1],(int)pec);
+ return 0;
+ } else {
+ warnx("CurPEC ok: %x",(int)pec);
+ }
+
+ // copy data
+ memcpy(data, &buff[1], bufflen);
+
+ // optionally add zero to end
+ if (append_zero) {
+ data[bufflen] = '\0';
+ }
+
+ // return success
+ return bufflen;
+}
+
+// get_PEC - calculate PEC for a read or write from the battery
+// buff is the data that was read or will be written
+uint8_t BATT_SMBUS::get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const
+{
+ // exit immediately if no data
+ if (len <= 0) {
+ return 0;
+ }
+
+ // prepare temp buffer for calcing crc
+ uint8_t tmp_buff[len+3];
+ tmp_buff[0] = (uint8_t)get_address() << 1;
+ tmp_buff[1] = cmd;
+ tmp_buff[2] = tmp_buff[0] | (uint8_t)reading;
+ memcpy(&tmp_buff[3],buff,len);
+
+ // initialise crc to zero
+ uint8_t crc = 0;
+ uint8_t shift_reg = 0;
+ bool do_invert;
+
+ // for each byte in the stream
+ for (uint8_t i=0; i<sizeof(tmp_buff); i++) {
+ // load next data byte into the shift register
+ shift_reg = tmp_buff[i];
+ // for each bit in the current byte
+ for (uint8_t j=0; j<8; j++) {
+ do_invert = (crc ^ shift_reg) & 0x80;
+ crc <<= 1;
+ shift_reg <<= 1;
+ if (do_invert) {
+ crc ^= BATT_SMBUS_PEC_POLYNOMIAL;
+ }
+ }
+ }
+
+ // return result
+ return crc;
+}
+
+///////////////////////// shell functions ///////////////////////
+
+void
+batt_smbus_usage()
+{
+ warnx("missing command: try 'start', 'test', 'stop', 'search'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", BATT_SMBUS_I2C_BUS);
+ warnx(" -a addr (0x%x)", BATT_SMBUS_ADDR);
+}
+
+int
+batt_smbus_main(int argc, char *argv[])
+{
+ int i2cdevice = BATT_SMBUS_I2C_BUS;
+ int batt_smbusadr = BATT_SMBUS_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':
+ batt_smbusadr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ batt_smbus_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ batt_smbus_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ if (!strcmp(verb, "start")) {
+ if (g_batt_smbus != nullptr) {
+ errx(1, "already started");
+ } else {
+ // create new global object
+ g_batt_smbus = new BATT_SMBUS(i2cdevice, batt_smbusadr);
+
+ if (g_batt_smbus == nullptr) {
+ errx(1, "new failed");
+ }
+
+ if (OK != g_batt_smbus->init()) {
+ delete g_batt_smbus;
+ g_batt_smbus = nullptr;
+ errx(1, "init failed");
+ }
+ }
+
+ exit(0);
+ }
+
+ /* need the driver past this point */
+ if (g_batt_smbus == nullptr) {
+ warnx("not started");
+ batt_smbus_usage();
+ exit(1);
+ }
+
+ if (!strcmp(verb, "test")) {
+ g_batt_smbus->test();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "stop")) {
+ delete g_batt_smbus;
+ g_batt_smbus = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(verb, "search")) {
+ g_batt_smbus->search();
+ exit(0);
+ }
+
+ batt_smbus_usage();
+ exit(0);
+}
diff --git a/src/drivers/batt_smbus/module.mk b/src/drivers/batt_smbus/module.mk
new file mode 100644
index 000000000..b32ea6e55
--- /dev/null
+++ b/src/drivers/batt_smbus/module.mk
@@ -0,0 +1,8 @@
+#
+# driver for SMBus smart batteries
+#
+
+MODULE_COMMAND = batt_smbus
+SRCS = batt_smbus.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 705b398b0..206e71ddc 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -58,7 +58,7 @@ public:
/**
* Get the address
*/
- int16_t get_address() { return _address; }
+ int16_t get_address() const { return _address; }
protected:
/**
diff --git a/src/drivers/drv_batt_smbus.h b/src/drivers/drv_batt_smbus.h
new file mode 100644
index 000000000..ca130c84e
--- /dev/null
+++ b/src/drivers/drv_batt_smbus.h
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * 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_batt_smbus.h
+ *
+ * SMBus battery monitor device API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+#include "drv_orb_dev.h"
+
+/* device path */
+#define BATT_SMBUS_DEVICE_PATH "/dev/batt_smbus"
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index ab640837b..5aed3f02b 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file Rangefinder driver interface.
+ * @file PX4Flow driver interface.
*/
#ifndef _DRV_PX4FLOW_H
diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h
index 8e8b2c1b9..5e4598de8 100644
--- a/src/drivers/drv_sensor.h
+++ b/src/drivers/drv_sensor.h
@@ -82,8 +82,19 @@
#define SENSORIOCGQUEUEDEPTH _SENSORIOC(3)
/**
- * Reset the sensor to its default configuration.
+ * Reset the sensor to its default configuration
*/
#define SENSORIOCRESET _SENSORIOC(4)
-#endif /* _DRV_SENSOR_H */ \ No newline at end of file
+/**
+ * Set the sensor orientation
+ */
+#define SENSORIOCSROTATION _SENSORIOC(5)
+
+/**
+ * Get the sensor orientation
+ */
+#define SENSORIOCGROTATION _SENSORIOC(6)
+
+#endif /* _DRV_SENSOR_H */
+
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 82fa5cc6e..08bc1fead 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -142,6 +142,7 @@ static const int ERROR = -1;
#define ADDR_INT1_TSH_ZH 0x36
#define ADDR_INT1_TSH_ZL 0x37
#define ADDR_INT1_DURATION 0x38
+#define ADDR_LOW_ODR 0x39
/* Internal configuration values */
@@ -200,6 +201,12 @@ public:
*/
void print_info();
+ // print register dump
+ void print_registers();
+
+ // trigger an error
+ void test_error();
+
protected:
virtual int probe();
@@ -225,6 +232,9 @@ private:
perf_counter_t _sample_perf;
perf_counter_t _reschedules;
perf_counter_t _errors;
+ perf_counter_t _bad_registers;
+
+ uint8_t _register_wait;
math::LowPassFilter2p _gyro_filter_x;
math::LowPassFilter2p _gyro_filter_y;
@@ -235,6 +245,14 @@ private:
enum Rotation _rotation;
+ // this is used to support runtime checking of key
+ // configuration registers to detect SPI bus errors and sensor
+ // reset
+#define L3GD20_NUM_CHECKED_REGISTERS 8
+ static const uint8_t _checked_registers[L3GD20_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_values[L3GD20_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_next;
+
/**
* Start automatic measurement.
*/
@@ -267,6 +285,11 @@ private:
static void measure_trampoline(void *arg);
/**
+ * check key registers for correct values
+ */
+ void check_registers(void);
+
+ /**
* Fetch measurements from the sensor and update the report ring.
*/
void measure();
@@ -299,6 +322,14 @@ private:
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
/**
+ * Write a register in the L3GD20, updating _checked_values
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_checked_reg(unsigned reg, uint8_t value);
+
+ /**
* Set the L3GD20 measurement range.
*
* @param max_dps The measurement range is set to permit reading at least
@@ -338,6 +369,19 @@ private:
L3GD20 operator=(const L3GD20&);
};
+/*
+ list of registers that will be checked in check_registers(). Note
+ that ADDR_WHO_AM_I must be first in the list.
+ */
+const uint8_t L3GD20::_checked_registers[L3GD20_NUM_CHECKED_REGISTERS] = { ADDR_WHO_AM_I,
+ ADDR_CTRL_REG1,
+ ADDR_CTRL_REG2,
+ ADDR_CTRL_REG3,
+ ADDR_CTRL_REG4,
+ ADDR_CTRL_REG5,
+ ADDR_FIFO_CTRL_REG,
+ ADDR_LOW_ODR };
+
L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation) :
SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */),
_call{},
@@ -355,11 +399,14 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotati
_sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
_reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
_errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
+ _bad_registers(perf_alloc(PC_COUNT, "l3gd20_bad_registers")),
+ _register_wait(0),
_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),
_is_l3g4200d(false),
- _rotation(rotation)
+ _rotation(rotation),
+ _checked_next(0)
{
// enable debug() calls
_debug_enabled = true;
@@ -389,6 +436,7 @@ L3GD20::~L3GD20()
perf_free(_sample_perf);
perf_free(_reschedules);
perf_free(_errors);
+ perf_free(_bad_registers);
}
int
@@ -448,29 +496,27 @@ L3GD20::probe()
(void)read_reg(ADDR_WHO_AM_I);
bool success = false;
+ uint8_t v = 0;
- /* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
-
+ /* verify that the device is attached and functioning, accept
+ * L3GD20, L3GD20H and L3G4200D */
+ if ((v=read_reg(ADDR_WHO_AM_I)) == WHO_I_AM) {
_orientation = SENSOR_BOARD_ROTATION_DEFAULT;
success = true;
- }
-
-
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_H) {
+ } else if ((v=read_reg(ADDR_WHO_AM_I)) == WHO_I_AM_H) {
_orientation = SENSOR_BOARD_ROTATION_180_DEG;
success = true;
- }
-
- /* Detect the L3G4200D used on AeroCore */
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_L3G4200D) {
+ } else if ((v=read_reg(ADDR_WHO_AM_I)) == WHO_I_AM_L3G4200D) {
+ /* Detect the L3G4200D used on AeroCore */
_is_l3g4200d = true;
_orientation = SENSOR_BOARD_ROTATION_DEFAULT;
success = true;
}
- if (success)
+ if (success) {
+ _checked_values[0] = v;
return OK;
+ }
return -EIO;
}
@@ -673,6 +719,18 @@ L3GD20::write_reg(unsigned reg, uint8_t value)
}
void
+L3GD20::write_checked_reg(unsigned reg, uint8_t value)
+{
+ write_reg(reg, value);
+ for (uint8_t i=0; i<L3GD20_NUM_CHECKED_REGISTERS; i++) {
+ if (reg == _checked_registers[i]) {
+ _checked_values[i] = value;
+ }
+ }
+}
+
+
+void
L3GD20::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
{
uint8_t val;
@@ -680,7 +738,7 @@ L3GD20::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
val = read_reg(reg);
val &= ~clearbits;
val |= setbits;
- write_reg(reg, val);
+ write_checked_reg(reg, val);
}
int
@@ -714,7 +772,7 @@ L3GD20::set_range(unsigned max_dps)
_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);
+ write_checked_reg(ADDR_CTRL_REG4, bits);
return OK;
}
@@ -750,7 +808,7 @@ L3GD20::set_samplerate(unsigned frequency)
return -EINVAL;
}
- write_reg(ADDR_CTRL_REG1, bits);
+ write_checked_reg(ADDR_CTRL_REG1, bits);
return OK;
}
@@ -791,6 +849,11 @@ L3GD20::disable_i2c(void)
uint8_t a = read_reg(0x05);
write_reg(0x05, (0x20 | a));
if (read_reg(0x05) == (a | 0x20)) {
+ // this sets the I2C_DIS bit on the
+ // L3GD20H. The l3gd20 datasheet doesn't
+ // mention this register, but it does seem to
+ // accept it.
+ write_checked_reg(ADDR_LOW_ODR, 0x08);
return;
}
}
@@ -804,18 +867,18 @@ L3GD20::reset()
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 */
+ write_checked_reg(ADDR_CTRL_REG1,
+ REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+ write_checked_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
+ write_checked_reg(ADDR_CTRL_REG3, 0x08); /* DRDY enable */
+ write_checked_reg(ADDR_CTRL_REG4, REG4_BDU);
+ write_checked_reg(ADDR_CTRL_REG5, 0);
+ write_checked_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);
+ write_checked_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
set_samplerate(0); // 760Hz or 800Hz
set_range(L3GD20_DEFAULT_RANGE_DPS);
@@ -840,19 +903,35 @@ L3GD20::measure_trampoline(void *arg)
#endif
void
-L3GD20::measure()
+L3GD20::check_registers(void)
{
-#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 (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
- perf_count(_reschedules);
- hrt_call_delay(&_call, 100);
- return;
- }
-#endif
+ uint8_t v;
+ if ((v=read_reg(_checked_registers[_checked_next])) != _checked_values[_checked_next]) {
+ /*
+ if we get the wrong value then we know the SPI bus
+ or sensor is very sick. We set _register_wait to 20
+ and wait until we have seen 20 good values in a row
+ before we consider the sensor to be OK again.
+ */
+ perf_count(_bad_registers);
+
+ /*
+ try to fix the bad register value. We only try to
+ fix one per loop to prevent a bad sensor hogging the
+ bus. We skip zero as that is the WHO_AM_I, which
+ is not writeable
+ */
+ if (_checked_next != 0) {
+ write_reg(_checked_registers[_checked_next], _checked_values[_checked_next]);
+ }
+ _register_wait = 20;
+ }
+ _checked_next = (_checked_next+1) % L3GD20_NUM_CHECKED_REGISTERS;
+}
+void
+L3GD20::measure()
+{
/* status register and data as read back from the device */
#pragma pack(push, 1)
struct {
@@ -870,6 +949,20 @@ L3GD20::measure()
/* start the performance counter */
perf_begin(_sample_perf);
+ check_registers();
+
+#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 (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
+ perf_count(_reschedules);
+ hrt_call_delay(&_call, 100);
+ perf_end(_sample_perf);
+ return;
+ }
+#endif
+
/* fetch data from the sensor */
memset(&raw_report, 0, sizeof(raw_report));
raw_report.cmd = ADDR_OUT_TEMP | DIR_READ | ADDR_INCREMENT;
@@ -900,7 +993,7 @@ L3GD20::measure()
* 74 from all measurements centers them around zero.
*/
report.timestamp = hrt_absolute_time();
- report.error_count = 0; // not recorded
+ report.error_count = perf_event_count(_bad_registers);
switch (_orientation) {
@@ -973,7 +1066,39 @@ L3GD20::print_info()
perf_print_counter(_sample_perf);
perf_print_counter(_reschedules);
perf_print_counter(_errors);
+ perf_print_counter(_bad_registers);
_reports->print_info("report queue");
+ ::printf("checked_next: %u\n", _checked_next);
+ for (uint8_t i=0; i<L3GD20_NUM_CHECKED_REGISTERS; i++) {
+ uint8_t v = read_reg(_checked_registers[i]);
+ if (v != _checked_values[i]) {
+ ::printf("reg %02x:%02x should be %02x\n",
+ (unsigned)_checked_registers[i],
+ (unsigned)v,
+ (unsigned)_checked_values[i]);
+ }
+ }
+}
+
+void
+L3GD20::print_registers()
+{
+ printf("L3GD20 registers\n");
+ for (uint8_t reg=0; reg<=0x40; reg++) {
+ uint8_t v = read_reg(reg);
+ printf("%02x:%02x ",(unsigned)reg, (unsigned)v);
+ if ((reg+1) % 16 == 0) {
+ printf("\n");
+ }
+ }
+ printf("\n");
+}
+
+void
+L3GD20::test_error()
+{
+ // trigger a deliberate error
+ write_reg(ADDR_CTRL_REG3, 0);
}
int
@@ -1011,6 +1136,8 @@ void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
+void regdump();
+void test_error();
/**
* Start the driver.
@@ -1149,10 +1276,40 @@ info()
exit(0);
}
+/**
+ * Dump the register information
+ */
+void
+regdump(void)
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running");
+
+ printf("regdump @ %p\n", g_dev);
+ g_dev->print_registers();
+
+ exit(0);
+}
+
+/**
+ * trigger an error
+ */
+void
+test_error(void)
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running");
+
+ printf("regdump @ %p\n", g_dev);
+ g_dev->test_error();
+
+ exit(0);
+}
+
void
usage()
{
- warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'testerror' or 'regdump'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
@@ -1209,5 +1366,17 @@ l3gd20_main(int argc, char *argv[])
if (!strcmp(verb, "info"))
l3gd20::info();
- errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+ /*
+ * Print register information.
+ */
+ if (!strcmp(verb, "regdump"))
+ l3gd20::regdump();
+
+ /*
+ * trigger an error
+ */
+ if (!strcmp(verb, "testerror"))
+ l3gd20::test_error();
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'testerror' or 'regdump'");
}
diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp
index 4676c6ad7..e68f24152 100644
--- a/src/drivers/ll40ls/ll40ls.cpp
+++ b/src/drivers/ll40ls/ll40ls.cpp
@@ -746,6 +746,9 @@ start(int bus)
if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
delete g_dev_ext;
g_dev_ext = nullptr;
+ if (bus == PX4_I2C_BUS_EXPANSION) {
+ goto fail;
+ }
}
}
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 01c89192a..00484db79 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -77,10 +77,6 @@
#endif
static const int ERROR = -1;
-// enable this to debug the buggy lsm303d sensor in very early
-// prototype pixhawk boards
-#define CHECK_EXTREMES 0
-
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
@@ -242,14 +238,9 @@ public:
void print_registers();
/**
- * toggle logging
- */
- void toggle_logging();
-
- /**
- * check for extreme accel values
+ * deliberately trigger an error
*/
- void check_extremes(const accel_report *arb);
+ void test_error();
protected:
virtual int probe();
@@ -292,30 +283,25 @@ private:
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;
+ perf_counter_t _bad_registers;
+
+ uint8_t _register_wait;
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;
enum Rotation _rotation;
+ // this is used to support runtime checking of key
+ // configuration registers to detect SPI bus errors and sensor
+ // reset
+#define LSM303D_NUM_CHECKED_REGISTERS 8
+ static const uint8_t _checked_registers[LSM303D_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_values[LSM303D_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_next;
+
/**
* Start automatic measurement.
*/
@@ -357,6 +343,11 @@ private:
static void mag_measure_trampoline(void *arg);
/**
+ * check key registers for correct values
+ */
+ void check_registers(void);
+
+ /**
* Fetch accel measurements from the sensor and update the report ring.
*/
void measure();
@@ -408,6 +399,14 @@ private:
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
/**
+ * Write a register in the LSM303D, updating _checked_values
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_checked_reg(unsigned reg, uint8_t value);
+
+ /**
* Set the LSM303D accel measurement range.
*
* @param max_g The measurement range of the accel is in g (9.81m/s^2)
@@ -468,6 +467,19 @@ private:
LSM303D operator=(const LSM303D&);
};
+/*
+ list of registers that will be checked in check_registers(). Note
+ that ADDR_WHO_AM_I must be first in the list.
+ */
+const uint8_t LSM303D::_checked_registers[LSM303D_NUM_CHECKED_REGISTERS] = { ADDR_WHO_AM_I,
+ ADDR_CTRL_REG1,
+ ADDR_CTRL_REG2,
+ ADDR_CTRL_REG3,
+ ADDR_CTRL_REG4,
+ ADDR_CTRL_REG5,
+ ADDR_CTRL_REG6,
+ ADDR_CTRL_REG7 };
+
/**
* Helper class implementing the mag driver node.
*/
@@ -528,23 +540,14 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota
_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")),
+ _bad_registers(perf_alloc(PC_COUNT, "lsm303d_bad_registers")),
+ _register_wait(0),
_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_extreme_us(0),
- _last_log_us(0),
- _last_log_sync_us(0),
- _last_log_reg_us(0),
- _last_log_alarm_us(0),
- _rotation(rotation)
+ _rotation(rotation),
+ _checked_next(0)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D;
@@ -586,9 +589,7 @@ LSM303D::~LSM303D()
/* 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(_bad_registers);
perf_free(_accel_reschedules);
}
@@ -703,15 +704,14 @@ LSM303D::reset()
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);
+ write_checked_reg(ADDR_CTRL_REG1,
+ REG1_X_ENABLE_A | REG1_Y_ENABLE_A | REG1_Z_ENABLE_A | REG1_BDU_UPDATE | REG1_RATE_800HZ_A);
/* 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
+ write_checked_reg(ADDR_CTRL_REG7, REG7_CONT_MODE_M);
+ write_checked_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
+ write_checked_reg(ADDR_CTRL_REG3, 0x04); // DRDY on ACCEL on INT1
+ write_checked_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);
@@ -739,126 +739,12 @@ LSM303D::probe()
/* verify that the device is attached and functioning */
bool success = (read_reg(ADDR_WHO_AM_I) == WHO_I_AM);
- if (success)
+ if (success) {
+ _checked_values[0] = WHO_I_AM;
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);
- }
- }
+ return -EIO;
}
ssize_t
@@ -879,9 +765,6 @@ LSM303D::read(struct file *filp, char *buffer, size_t buflen)
*/
while (count--) {
if (_accel_reports->get(arb)) {
-#if CHECK_EXTREMES
- check_extremes(arb);
-#endif
ret += sizeof(*arb);
arb++;
}
@@ -1263,6 +1146,17 @@ LSM303D::write_reg(unsigned reg, uint8_t value)
}
void
+LSM303D::write_checked_reg(unsigned reg, uint8_t value)
+{
+ write_reg(reg, value);
+ for (uint8_t i=0; i<LSM303D_NUM_CHECKED_REGISTERS; i++) {
+ if (reg == _checked_registers[i]) {
+ _checked_values[i] = value;
+ }
+ }
+}
+
+void
LSM303D::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
{
uint8_t val;
@@ -1270,7 +1164,7 @@ LSM303D::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
val = read_reg(reg);
val &= ~clearbits;
val |= setbits;
- write_reg(reg, val);
+ write_checked_reg(reg, val);
}
int
@@ -1439,7 +1333,6 @@ LSM303D::accel_set_samplerate(unsigned frequency)
}
modify_reg(ADDR_CTRL_REG1, clearbits, setbits);
- _reg1_expected = (_reg1_expected & ~clearbits) | setbits;
return OK;
}
@@ -1515,24 +1408,35 @@ LSM303D::mag_measure_trampoline(void *arg)
}
void
-LSM303D::measure()
+LSM303D::check_registers(void)
{
- // 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.
- // Note that DRDY is not available when the lsm303d is
- // connected on the external bus
- if (_bus == PX4_SPI_BUS_SENSORS && 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;
- }
+ uint8_t v;
+ if ((v=read_reg(_checked_registers[_checked_next])) != _checked_values[_checked_next]) {
+ /*
+ if we get the wrong value then we know the SPI bus
+ or sensor is very sick. We set _register_wait to 20
+ and wait until we have seen 20 good values in a row
+ before we consider the sensor to be OK again.
+ */
+ perf_count(_bad_registers);
+ /*
+ try to fix the bad register value. We only try to
+ fix one per loop to prevent a bad sensor hogging the
+ bus. We skip zero as that is the WHO_AM_I, which
+ is not writeable
+ */
+ if (_checked_next != 0) {
+ write_reg(_checked_registers[_checked_next], _checked_values[_checked_next]);
+ }
+ _register_wait = 20;
+ }
+ _checked_next = (_checked_next+1) % LSM303D_NUM_CHECKED_REGISTERS;
+}
+
+void
+LSM303D::measure()
+{
/* status register and data as read back from the device */
#pragma pack(push, 1)
@@ -1550,6 +1454,30 @@ LSM303D::measure()
/* start the performance counter */
perf_begin(_accel_sample_perf);
+ check_registers();
+
+ // 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.
+ // Note that DRDY is not available when the lsm303d is
+ // connected on the external bus
+#ifdef GPIO_EXTI_ACCEL_DRDY
+ if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
+ perf_count(_accel_reschedules);
+ hrt_call_delay(&_accel_call, 100);
+ perf_end(_accel_sample_perf);
+ return;
+ }
+#endif
+
+ if (_register_wait != 0) {
+ // we are waiting for some good transfers before using
+ // the sensor again.
+ _register_wait--;
+ perf_end(_accel_sample_perf);
+ return;
+ }
+
/* 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;
@@ -1572,7 +1500,12 @@ LSM303D::measure()
accel_report.timestamp = hrt_absolute_time();
- accel_report.error_count = 0; // not reported
+
+ // report the error count as the sum of the number of bad bad
+ // register reads. This allows the higher level code to decide
+ // if it should use this sensor based on whether it has had
+ // failures
+ accel_report.error_count = perf_event_count(_bad_registers);
accel_report.x_raw = raw_accel_report.x;
accel_report.y_raw = raw_accel_report.y;
@@ -1611,12 +1544,6 @@ LSM303D::measure()
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 {
@@ -1691,8 +1618,21 @@ LSM303D::print_info()
printf("accel reads: %u\n", _accel_read);
printf("mag reads: %u\n", _mag_read);
perf_print_counter(_accel_sample_perf);
+ perf_print_counter(_mag_sample_perf);
+ perf_print_counter(_bad_registers);
+ perf_print_counter(_accel_reschedules);
_accel_reports->print_info("accel reports");
_mag_reports->print_info("mag reports");
+ ::printf("checked_next: %u\n", _checked_next);
+ for (uint8_t i=0; i<LSM303D_NUM_CHECKED_REGISTERS; i++) {
+ uint8_t v = read_reg(_checked_registers[i]);
+ if (v != _checked_values[i]) {
+ ::printf("reg %02x:%02x should be %02x\n",
+ (unsigned)_checked_registers[i],
+ (unsigned)v,
+ (unsigned)_checked_values[i]);
+ }
+ }
}
void
@@ -1750,20 +1690,13 @@ LSM303D::print_registers()
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()
+LSM303D::test_error()
{
- 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");
- }
+ // trigger an error
+ write_reg(ADDR_CTRL_REG3, 0);
}
LSM303D_mag::LSM303D_mag(LSM303D *parent) :
@@ -1839,8 +1772,8 @@ void test();
void reset();
void info();
void regdump();
-void logging();
void usage();
+void test_error();
/**
* Start the driver.
@@ -2047,15 +1980,15 @@ regdump()
}
/**
- * toggle logging
+ * trigger an error
*/
void
-logging()
+test_error()
{
if (g_dev == nullptr)
errx(1, "driver not running\n");
- g_dev->toggle_logging();
+ g_dev->test_error();
exit(0);
}
@@ -2063,7 +1996,7 @@ logging()
void
usage()
{
- warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'logging'");
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'testerror' or 'regdump'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
@@ -2127,10 +2060,10 @@ lsm303d_main(int argc, char *argv[])
lsm303d::regdump();
/*
- * dump device registers
+ * trigger an error
*/
- if (!strcmp(verb, "logging"))
- lsm303d::logging();
+ if (!strcmp(verb, "testerror"))
+ lsm303d::test_error();
- errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'logging' or 'regdump'");
+ errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'testerror' or 'regdump'");
}
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index c9c27892f..6cac28a7d 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -113,6 +113,10 @@
#define MPUREG_FIFO_COUNTL 0x73
#define MPUREG_FIFO_R_W 0x74
#define MPUREG_PRODUCT_ID 0x0C
+#define MPUREG_TRIM1 0x0D
+#define MPUREG_TRIM2 0x0E
+#define MPUREG_TRIM3 0x0F
+#define MPUREG_TRIM4 0x10
// Configuration bits MPU 3000 and MPU 6000 (not revised)?
#define BIT_SLEEP 0x40
@@ -121,6 +125,9 @@
#define MPU_CLK_SEL_PLLGYROX 0x01
#define MPU_CLK_SEL_PLLGYROZ 0x03
#define MPU_EXT_SYNC_GYROX 0x02
+#define BITS_GYRO_ST_X 0x80
+#define BITS_GYRO_ST_Y 0x40
+#define BITS_GYRO_ST_Z 0x20
#define BITS_FS_250DPS 0x00
#define BITS_FS_500DPS 0x08
#define BITS_FS_1000DPS 0x10
@@ -196,6 +203,16 @@ public:
void print_registers();
+ /**
+ * Test behaviour against factory offsets
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int factory_self_test();
+
+ // deliberately cause a sensor error
+ void test_error();
+
protected:
virtual int probe();
@@ -231,7 +248,12 @@ private:
perf_counter_t _gyro_reads;
perf_counter_t _sample_perf;
perf_counter_t _bad_transfers;
+ perf_counter_t _bad_registers;
perf_counter_t _good_transfers;
+ perf_counter_t _reset_retries;
+
+ uint8_t _register_wait;
+ uint64_t _reset_wait;
math::LowPassFilter2p _accel_filter_x;
math::LowPassFilter2p _accel_filter_y;
@@ -242,6 +264,18 @@ private:
enum Rotation _rotation;
+ // this is used to support runtime checking of key
+ // configuration registers to detect SPI bus errors and sensor
+ // reset
+#define MPU6000_NUM_CHECKED_REGISTERS 9
+ static const uint8_t _checked_registers[MPU6000_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_values[MPU6000_NUM_CHECKED_REGISTERS];
+ uint8_t _checked_next;
+
+ // use this to avoid processing measurements when in factory
+ // self test
+ volatile bool _in_factory_test;
+
/**
* Start automatic measurement.
*/
@@ -257,7 +291,7 @@ private:
*
* Resets the chip and measurements ranges, but not scale and offset.
*/
- void reset();
+ int reset();
/**
* Static trampoline from the hrt_call context; because we don't have a
@@ -281,7 +315,7 @@ private:
* @param The register to read.
* @return The value that was read.
*/
- uint8_t read_reg(unsigned reg);
+ uint8_t read_reg(unsigned reg, uint32_t speed=MPU6000_LOW_BUS_SPEED);
uint16_t read_reg16(unsigned reg);
/**
@@ -304,6 +338,14 @@ private:
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
/**
+ * Write a register in the MPU6000, updating _checked_values
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_checked_reg(unsigned reg, uint8_t value);
+
+ /**
* Set the MPU6000 measurement range.
*
* @param max_g The maximum G value the range must support.
@@ -347,11 +389,50 @@ private:
*/
void _set_sample_rate(uint16_t desired_sample_rate_hz);
+ /*
+ check that key registers still have the right value
+ */
+ void check_registers(void);
+
/* do not allow to copy this class due to pointer data members */
MPU6000(const MPU6000&);
MPU6000 operator=(const MPU6000&);
+
+#pragma pack(push, 1)
+ /**
+ * Report conversation within the MPU6000, including command byte and
+ * interrupt status.
+ */
+ struct MPUReport {
+ uint8_t cmd;
+ uint8_t status;
+ uint8_t accel_x[2];
+ uint8_t accel_y[2];
+ uint8_t accel_z[2];
+ uint8_t temp[2];
+ uint8_t gyro_x[2];
+ uint8_t gyro_y[2];
+ uint8_t gyro_z[2];
+ };
+#pragma pack(pop)
};
+/*
+ list of registers that will be checked in check_registers(). Note
+ that MPUREG_PRODUCT_ID must be first in the list.
+ */
+const uint8_t MPU6000::_checked_registers[MPU6000_NUM_CHECKED_REGISTERS] = { MPUREG_PRODUCT_ID,
+ MPUREG_PWR_MGMT_1,
+ MPUREG_USER_CTRL,
+ MPUREG_SMPLRT_DIV,
+ MPUREG_CONFIG,
+ MPUREG_GYRO_CONFIG,
+ MPUREG_ACCEL_CONFIG,
+ MPUREG_INT_ENABLE,
+ MPUREG_INT_PIN_CFG };
+
+
+
/**
* Helper class implementing the gyro driver node.
*/
@@ -407,14 +488,20 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev
_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")),
+ _bad_registers(perf_alloc(PC_COUNT, "mpu6000_bad_registers")),
_good_transfers(perf_alloc(PC_COUNT, "mpu6000_good_transfers")),
+ _reset_retries(perf_alloc(PC_COUNT, "mpu6000_reset_retries")),
+ _register_wait(0),
+ _reset_wait(0),
_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),
- _rotation(rotation)
+ _rotation(rotation),
+ _checked_next(0),
+ _in_factory_test(false)
{
// disable debug() calls
_debug_enabled = false;
@@ -460,6 +547,7 @@ MPU6000::~MPU6000()
perf_free(_accel_reads);
perf_free(_gyro_reads);
perf_free(_bad_transfers);
+ perf_free(_bad_registers);
perf_free(_good_transfers);
}
@@ -486,7 +574,8 @@ MPU6000::init()
if (_gyro_reports == nullptr)
goto out;
- reset();
+ if (reset() != OK)
+ goto out;
/* Initialize offsets and scales */
_accel_scale.x_offset = 0;
@@ -571,27 +660,39 @@ out:
return ret;
}
-void MPU6000::reset()
+int 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();
-
- write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
- up_udelay(10000);
-
- // 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);
+ uint8_t tries = 5;
+ while (--tries != 0) {
+ irqstate_t state;
+ state = irqsave();
+
+ write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
+ up_udelay(10000);
+
+ // 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_checked_reg(MPUREG_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
+ up_udelay(1000);
+
+ // Disable I2C bus (recommended on datasheet)
+ write_checked_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
+ irqrestore(state);
- // Disable I2C bus (recommended on datasheet)
- write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
- irqrestore(state);
+ if (read_reg(MPUREG_PWR_MGMT_1) == MPU_CLK_SEL_PLLGYROZ) {
+ break;
+ }
+ perf_count(_reset_retries);
+ usleep(2000);
+ }
+ if (read_reg(MPUREG_PWR_MGMT_1) != MPU_CLK_SEL_PLLGYROZ) {
+ return -EIO;
+ }
usleep(1000);
@@ -605,7 +706,7 @@ void MPU6000::reset()
_set_dlpf_filter(MPU6000_DEFAULT_ONCHIP_FILTER_FREQ);
usleep(1000);
// Gyro scale 2000 deg/s ()
- write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
+ write_checked_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
usleep(1000);
// correct gyro scale factors
@@ -624,7 +725,7 @@ void MPU6000::reset()
case MPU6000_REV_C5:
// Accel scale 8g (4096 LSB/g)
// Rev C has different scaling than rev D
- write_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
+ write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
break;
case MPU6000ES_REV_D6:
@@ -639,7 +740,7 @@ void MPU6000::reset()
// presumably won't have the accel scaling bug
default:
// Accel scale 8g (4096 LSB/g)
- write_reg(MPUREG_ACCEL_CONFIG, 2 << 3);
+ write_checked_reg(MPUREG_ACCEL_CONFIG, 2 << 3);
break;
}
@@ -651,15 +752,16 @@ void MPU6000::reset()
usleep(1000);
// INT CFG => Interrupt on Data Ready
- write_reg(MPUREG_INT_ENABLE, BIT_RAW_RDY_EN); // INT: Raw data ready
+ write_checked_reg(MPUREG_INT_ENABLE, BIT_RAW_RDY_EN); // INT: Raw data ready
usleep(1000);
- write_reg(MPUREG_INT_PIN_CFG, BIT_INT_ANYRD_2CLEAR); // INT: Clear on any read
+ write_checked_reg(MPUREG_INT_PIN_CFG, BIT_INT_ANYRD_2CLEAR); // INT: Clear on any read
usleep(1000);
// Oscillator set
// write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
usleep(1000);
+ return OK;
}
int
@@ -684,6 +786,7 @@ MPU6000::probe()
case MPU6000_REV_D9:
case MPU6000_REV_D10:
debug("ID 0x%02x", _product);
+ _checked_values[0] = _product;
return OK;
}
@@ -700,7 +803,7 @@ 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);
+ write_checked_reg(MPUREG_SMPLRT_DIV, div-1);
_sample_rate = 1000 / div;
}
@@ -734,7 +837,7 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
} else {
filter = BITS_DLPF_CFG_2100HZ_NOLPF;
}
- write_reg(MPUREG_CONFIG, filter);
+ write_checked_reg(MPUREG_CONFIG, filter);
}
ssize_t
@@ -833,6 +936,173 @@ MPU6000::gyro_self_test()
return 0;
}
+
+/*
+ perform a self-test comparison to factory trim values. This takes
+ about 200ms and will return OK if the current values are within 14%
+ of the expected values (as per datasheet)
+ */
+int
+MPU6000::factory_self_test()
+{
+ _in_factory_test = true;
+ uint8_t saved_gyro_config = read_reg(MPUREG_GYRO_CONFIG);
+ uint8_t saved_accel_config = read_reg(MPUREG_ACCEL_CONFIG);
+ const uint16_t repeats = 100;
+ int ret = OK;
+
+ // gyro self test has to be done at 250DPS
+ write_reg(MPUREG_GYRO_CONFIG, BITS_FS_250DPS);
+
+ struct MPUReport mpu_report;
+ float accel_baseline[3];
+ float gyro_baseline[3];
+ float accel[3];
+ float gyro[3];
+ float accel_ftrim[3];
+ float gyro_ftrim[3];
+
+ // get baseline values without self-test enabled
+ set_frequency(MPU6000_HIGH_BUS_SPEED);
+
+ memset(accel_baseline, 0, sizeof(accel_baseline));
+ memset(gyro_baseline, 0, sizeof(gyro_baseline));
+ memset(accel, 0, sizeof(accel));
+ memset(gyro, 0, sizeof(gyro));
+
+ for (uint8_t i=0; i<repeats; i++) {
+ up_udelay(1000);
+ mpu_report.cmd = DIR_READ | MPUREG_INT_STATUS;
+ transfer((uint8_t *)&mpu_report, ((uint8_t *)&mpu_report), sizeof(mpu_report));
+
+ accel_baseline[0] += int16_t_from_bytes(mpu_report.accel_x);
+ accel_baseline[1] += int16_t_from_bytes(mpu_report.accel_y);
+ accel_baseline[2] += int16_t_from_bytes(mpu_report.accel_z);
+ gyro_baseline[0] += int16_t_from_bytes(mpu_report.gyro_x);
+ gyro_baseline[1] += int16_t_from_bytes(mpu_report.gyro_y);
+ gyro_baseline[2] += int16_t_from_bytes(mpu_report.gyro_z);
+ }
+
+#if 1
+ write_reg(MPUREG_GYRO_CONFIG,
+ BITS_FS_250DPS |
+ BITS_GYRO_ST_X |
+ BITS_GYRO_ST_Y |
+ BITS_GYRO_ST_Z);
+
+ // accel 8g, self-test enabled all axes
+ write_reg(MPUREG_ACCEL_CONFIG, saved_accel_config | 0xE0);
+#endif
+
+ up_udelay(20000);
+
+ // get values with self-test enabled
+ set_frequency(MPU6000_HIGH_BUS_SPEED);
+
+
+ for (uint8_t i=0; i<repeats; i++) {
+ up_udelay(1000);
+ mpu_report.cmd = DIR_READ | MPUREG_INT_STATUS;
+ transfer((uint8_t *)&mpu_report, ((uint8_t *)&mpu_report), sizeof(mpu_report));
+ accel[0] += int16_t_from_bytes(mpu_report.accel_x);
+ accel[1] += int16_t_from_bytes(mpu_report.accel_y);
+ accel[2] += int16_t_from_bytes(mpu_report.accel_z);
+ gyro[0] += int16_t_from_bytes(mpu_report.gyro_x);
+ gyro[1] += int16_t_from_bytes(mpu_report.gyro_y);
+ gyro[2] += int16_t_from_bytes(mpu_report.gyro_z);
+ }
+
+ for (uint8_t i=0; i<3; i++) {
+ accel_baseline[i] /= repeats;
+ gyro_baseline[i] /= repeats;
+ accel[i] /= repeats;
+ gyro[i] /= repeats;
+ }
+
+ // extract factory trim values
+ uint8_t trims[4];
+ trims[0] = read_reg(MPUREG_TRIM1);
+ trims[1] = read_reg(MPUREG_TRIM2);
+ trims[2] = read_reg(MPUREG_TRIM3);
+ trims[3] = read_reg(MPUREG_TRIM4);
+ uint8_t atrim[3];
+ uint8_t gtrim[3];
+
+ atrim[0] = ((trims[0]>>3)&0x1C) | ((trims[3]>>4)&0x03);
+ atrim[1] = ((trims[1]>>3)&0x1C) | ((trims[3]>>2)&0x03);
+ atrim[2] = ((trims[2]>>3)&0x1C) | ((trims[3]>>0)&0x03);
+ gtrim[0] = trims[0] & 0x1F;
+ gtrim[1] = trims[1] & 0x1F;
+ gtrim[2] = trims[2] & 0x1F;
+
+ // convert factory trims to right units
+ for (uint8_t i=0; i<3; i++) {
+ accel_ftrim[i] = 4096 * 0.34f * powf(0.92f/0.34f, (atrim[i]-1)/30.0f);
+ gyro_ftrim[i] = 25 * 131.0f * powf(1.046f, gtrim[i]-1);
+ }
+ // Y gyro trim is negative
+ gyro_ftrim[1] *= -1;
+
+ for (uint8_t i=0; i<3; i++) {
+ float diff = accel[i]-accel_baseline[i];
+ float err = 100*(diff - accel_ftrim[i]) / accel_ftrim[i];
+ ::printf("ACCEL[%u] baseline=%d accel=%d diff=%d ftrim=%d err=%d\n",
+ (unsigned)i,
+ (int)(1000*accel_baseline[i]),
+ (int)(1000*accel[i]),
+ (int)(1000*diff),
+ (int)(1000*accel_ftrim[i]),
+ (int)err);
+ if (fabsf(err) > 14) {
+ ::printf("FAIL\n");
+ ret = -EIO;
+ }
+ }
+ for (uint8_t i=0; i<3; i++) {
+ float diff = gyro[i]-gyro_baseline[i];
+ float err = 100*(diff - gyro_ftrim[i]) / gyro_ftrim[i];
+ ::printf("GYRO[%u] baseline=%d gyro=%d diff=%d ftrim=%d err=%d\n",
+ (unsigned)i,
+ (int)(1000*gyro_baseline[i]),
+ (int)(1000*gyro[i]),
+ (int)(1000*(gyro[i]-gyro_baseline[i])),
+ (int)(1000*gyro_ftrim[i]),
+ (int)err);
+ if (fabsf(err) > 14) {
+ ::printf("FAIL\n");
+ ret = -EIO;
+ }
+ }
+
+ write_reg(MPUREG_GYRO_CONFIG, saved_gyro_config);
+ write_reg(MPUREG_ACCEL_CONFIG, saved_accel_config);
+
+ _in_factory_test = false;
+ if (ret == OK) {
+ ::printf("PASSED\n");
+ }
+
+ return ret;
+}
+
+
+/*
+ deliberately trigger an error in the sensor to trigger recovery
+ */
+void
+MPU6000::test_error()
+{
+ _in_factory_test = true;
+ // deliberately trigger an error. This was noticed during
+ // development as a handy way to test the reset logic
+ uint8_t data[16];
+ memset(data, 0, sizeof(data));
+ transfer(data, data, sizeof(data));
+ ::printf("error triggered\n");
+ print_registers();
+ _in_factory_test = false;
+}
+
ssize_t
MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
@@ -874,8 +1144,7 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
switch (cmd) {
case SENSORIOCRESET:
- reset();
- return OK;
+ return reset();
case SENSORIOCSPOLLRATE: {
switch (arg) {
@@ -1094,12 +1363,12 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
}
uint8_t
-MPU6000::read_reg(unsigned reg)
+MPU6000::read_reg(unsigned reg, uint32_t speed)
{
uint8_t cmd[2] = { (uint8_t)(reg | DIR_READ), 0};
// general register transfer at low clock speed
- set_frequency(MPU6000_LOW_BUS_SPEED);
+ set_frequency(speed);
transfer(cmd, cmd, sizeof(cmd));
@@ -1144,6 +1413,17 @@ MPU6000::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
write_reg(reg, val);
}
+void
+MPU6000::write_checked_reg(unsigned reg, uint8_t value)
+{
+ write_reg(reg, value);
+ for (uint8_t i=0; i<MPU6000_NUM_CHECKED_REGISTERS; i++) {
+ if (reg == _checked_registers[i]) {
+ _checked_values[i] = value;
+ }
+ }
+}
+
int
MPU6000::set_range(unsigned max_g)
{
@@ -1216,26 +1496,71 @@ MPU6000::measure_trampoline(void *arg)
}
void
+MPU6000::check_registers(void)
+{
+ /*
+ we read the register at full speed, even though it isn't
+ listed as a high speed register. The low speed requirement
+ for some registers seems to be a propgation delay
+ requirement for changing sensor configuration, which should
+ not apply to reading a single register. It is also a better
+ test of SPI bus health to read at the same speed as we read
+ the data registers.
+ */
+ uint8_t v;
+ if ((v=read_reg(_checked_registers[_checked_next], MPU6000_HIGH_BUS_SPEED)) !=
+ _checked_values[_checked_next]) {
+ /*
+ if we get the wrong value then we know the SPI bus
+ or sensor is very sick. We set _register_wait to 20
+ and wait until we have seen 20 good values in a row
+ before we consider the sensor to be OK again.
+ */
+ perf_count(_bad_registers);
+
+ /*
+ try to fix the bad register value. We only try to
+ fix one per loop to prevent a bad sensor hogging the
+ bus.
+ */
+ if (_register_wait == 0 || _checked_next == 0) {
+ // if the product_id is wrong then reset the
+ // sensor completely
+ write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
+ // after doing a reset we need to wait a long
+ // time before we do any other register writes
+ // or we will end up with the mpu6000 in a
+ // bizarre state where it has all correct
+ // register values but large offsets on the
+ // accel axes
+ _reset_wait = hrt_absolute_time() + 10000;
+ _checked_next = 0;
+ } else {
+ write_reg(_checked_registers[_checked_next], _checked_values[_checked_next]);
+ // waiting 3ms between register writes seems
+ // to raise the chance of the sensor
+ // recovering considerably
+ _reset_wait = hrt_absolute_time() + 3000;
+ }
+ _register_wait = 20;
+ }
+ _checked_next = (_checked_next+1) % MPU6000_NUM_CHECKED_REGISTERS;
+}
+
+void
MPU6000::measure()
{
-#pragma pack(push, 1)
- /**
- * Report conversation within the MPU6000, including command byte and
- * interrupt status.
- */
- struct MPUReport {
- uint8_t cmd;
- uint8_t status;
- uint8_t accel_x[2];
- uint8_t accel_y[2];
- uint8_t accel_z[2];
- uint8_t temp[2];
- uint8_t gyro_x[2];
- uint8_t gyro_y[2];
- uint8_t gyro_z[2];
- } mpu_report;
-#pragma pack(pop)
+ if (_in_factory_test) {
+ // don't publish any data while in factory test mode
+ return;
+ }
+
+ if (hrt_absolute_time() < _reset_wait) {
+ // we're waiting for a reset to complete
+ return;
+ }
+ struct MPUReport mpu_report;
struct Report {
int16_t accel_x;
int16_t accel_y;
@@ -1254,6 +1579,8 @@ MPU6000::measure()
*/
mpu_report.cmd = DIR_READ | MPUREG_INT_STATUS;
+ check_registers();
+
// sensor transfer at high clock speed
set_frequency(MPU6000_HIGH_BUS_SPEED);
@@ -1292,6 +1619,14 @@ MPU6000::measure()
}
perf_count(_good_transfers);
+
+ if (_register_wait != 0) {
+ // we are waiting for some good transfers before using
+ // the sensor again. We still increment
+ // _good_transfers, but don't return any data yet
+ _register_wait--;
+ return;
+ }
/*
@@ -1321,7 +1656,12 @@ MPU6000::measure()
* Adjust and scale results to m/s^2.
*/
grb.timestamp = arb.timestamp = hrt_absolute_time();
- grb.error_count = arb.error_count = 0; // not reported
+
+ // report the error count as the sum of the number of bad
+ // transfers and bad register reads. This allows the higher
+ // level code to decide if it should use this sensor based on
+ // whether it has had failures
+ grb.error_count = arb.error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers);
/*
* 1) Scale raw value to SI units using scaling from datasheet.
@@ -1411,9 +1751,21 @@ MPU6000::print_info()
perf_print_counter(_accel_reads);
perf_print_counter(_gyro_reads);
perf_print_counter(_bad_transfers);
+ perf_print_counter(_bad_registers);
perf_print_counter(_good_transfers);
+ perf_print_counter(_reset_retries);
_accel_reports->print_info("accel queue");
_gyro_reports->print_info("gyro queue");
+ ::printf("checked_next: %u\n", _checked_next);
+ for (uint8_t i=0; i<MPU6000_NUM_CHECKED_REGISTERS; i++) {
+ uint8_t v = read_reg(_checked_registers[i], MPU6000_HIGH_BUS_SPEED);
+ if (v != _checked_values[i]) {
+ ::printf("reg %02x:%02x should be %02x\n",
+ (unsigned)_checked_registers[i],
+ (unsigned)v,
+ (unsigned)_checked_values[i]);
+ }
+ }
}
void
@@ -1497,6 +1849,8 @@ void test(bool);
void reset(bool);
void info(bool);
void regdump(bool);
+void testerror(bool);
+void factorytest(bool);
void usage();
/**
@@ -1688,10 +2042,40 @@ regdump(bool external_bus)
exit(0);
}
+/**
+ * deliberately produce an error to test recovery
+ */
+void
+testerror(bool external_bus)
+{
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
+ errx(1, "driver not running");
+
+ (*g_dev_ptr)->test_error();
+
+ exit(0);
+}
+
+/**
+ * Dump the register information
+ */
+void
+factorytest(bool external_bus)
+{
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
+ errx(1, "driver not running");
+
+ (*g_dev_ptr)->factory_self_test();
+
+ exit(0);
+}
+
void
usage()
{
- warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump'");
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'factorytest', 'testerror'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
@@ -1754,5 +2138,11 @@ mpu6000_main(int argc, char *argv[])
if (!strcmp(verb, "regdump"))
mpu6000::regdump(external_bus);
- errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info' or 'regdump'");
+ if (!strcmp(verb, "factorytest"))
+ mpu6000::factorytest(external_bus);
+
+ if (!strcmp(verb, "testerror"))
+ mpu6000::testerror(external_bus);
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'regdump', 'factorytest' or 'testerror'");
}
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index 62308fc65..9c9c1b0f8 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -62,6 +62,8 @@
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
+#include <conversion/rotation.h>
+
#include <drivers/drv_hrt.h>
#include <drivers/drv_px4flow.h>
#include <drivers/device/ringbuffer.h>
@@ -73,13 +75,14 @@
#include <board_config.h>
/* Configuration Constants */
-#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
-//range 0x42 - 0x49
+#define I2C_FLOW_ADDRESS 0x42 ///< 7-bit address. 8-bit address is 0x84, range 0x42 - 0x49
/* PX4FLOW Registers addresses */
-#define PX4FLOW_REG 0x16 /* Measure Register 22*/
+#define PX4FLOW_REG 0x16 ///< Measure Register 22
+
+#define PX4FLOW_CONVERSION_INTERVAL 20000 ///< in microseconds! 20000 = 50 Hz 100000 = 10Hz
+#define PX4FLOW_I2C_MAX_BUS_SPEED 400000 ///< 400 KHz maximum speed
-#define PX4FLOW_CONVERSION_INTERVAL 20000 //in microseconds! 20000 = 50 Hz 100000 = 10Hz
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
@@ -125,7 +128,7 @@ struct i2c_integral_frame f_integral;
class PX4FLOW: public device::I2C
{
public:
- PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS);
+ PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS, enum Rotation rotation = (enum Rotation)0);
virtual ~PX4FLOW();
virtual int init();
@@ -154,6 +157,8 @@ private:
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
+
+ enum Rotation _sensor_rotation;
/**
* Test whether the device supported by the driver is present at a
@@ -199,8 +204,8 @@ private:
*/
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
-PX4FLOW::PX4FLOW(int bus, int address) :
- I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000), //400khz
+PX4FLOW::PX4FLOW(int bus, int address, enum Rotation rotation) :
+ I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, PX4FLOW_I2C_MAX_BUS_SPEED), /* 100-400 KHz */
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
@@ -208,7 +213,8 @@ PX4FLOW::PX4FLOW(int bus, int address) :
_px4flow_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "px4flow_read")),
_comms_errors(perf_alloc(PC_COUNT, "px4flow_comms_errors")),
- _buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows"))
+ _buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows")),
+ _sensor_rotation(rotation)
{
// enable debug() calls
_debug_enabled = false;
@@ -361,6 +367,13 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCGQUEUEDEPTH:
return _reports->size();
+ case SENSORIOCSROTATION:
+ _sensor_rotation = (enum Rotation)arg;
+ return OK;
+
+ case SENSORIOCGROTATION:
+ return _sensor_rotation;
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
@@ -535,6 +548,10 @@ PX4FLOW::collect()
report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
report.sensor_id = 0;
+
+ /* rotate measurements according to parameter */
+ float zeroval = 0.0f;
+ rotate_3f(_sensor_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval);
if (_px4flow_topic < 0) {
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report);
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index ea3166051..086f291f6 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1098,6 +1098,10 @@ int commander_thread_main(int argc, char *argv[])
status.is_rotary_wing = false;
}
+ /* set vehicle_status.is_vtol flag */
+ status.is_vtol = (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) ||
+ (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
+
/* check and update system / component ID */
param_get(_param_system_id, &(status.system_id));
param_get(_param_component_id, &(status.component_id));
@@ -1119,6 +1123,8 @@ int commander_thread_main(int argc, char *argv[])
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
+
+ /* Safety parameters */
param_get(_param_enable_parachute, &parachute_enabled);
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
param_get(_param_datalink_loss_timeout, &datalink_loss_timeout);
@@ -1127,6 +1133,8 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_ef_throttle_thres, &ef_throttle_thres);
param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
param_get(_param_ef_time_thres, &ef_time_thres);
+
+ /* Autostart id */
param_get(_param_autostart_id, &autostart_id);
}
@@ -1259,7 +1267,7 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
/* vtol status changed */
orb_copy(ORB_ID(vtol_vehicle_status), vtol_vehicle_status_sub, &vtol_status);
-
+ status.vtol_fw_permanent_stab = vtol_status.fw_permanent_stab;
/* Make sure that this is only adjusted if vehicle realy is of type vtol*/
if (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR || VEHICLE_TYPE_VTOL_QUADROTOR) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
@@ -2230,14 +2238,7 @@ set_control_mode()
{
/* set vehicle_control_mode according to set_navigation_state */
control_mode.flag_armed = armed.armed;
- /* TODO: check this */
- if (autostart_id < 13000 || autostart_id >= 14000) {
- control_mode.flag_external_manual_override_ok = !status.is_rotary_wing;
-
- } else {
- control_mode.flag_external_manual_override_ok = false;
- }
-
+ control_mode.flag_external_manual_override_ok = (!status.is_rotary_wing && !status.is_vtol);
control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON;
control_mode.flag_control_offboard_enabled = false;
@@ -2245,8 +2246,8 @@ set_control_mode()
case NAVIGATION_STATE_MANUAL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
- control_mode.flag_control_rates_enabled = status.is_rotary_wing;
- control_mode.flag_control_attitude_enabled = status.is_rotary_wing;
+ control_mode.flag_control_rates_enabled = (status.is_rotary_wing || status.vtol_fw_permanent_stab);
+ control_mode.flag_control_attitude_enabled = (status.is_rotary_wing || status.vtol_fw_permanent_stab);
control_mode.flag_control_altitude_enabled = false;
control_mode.flag_control_climb_rate_enabled = false;
control_mode.flag_control_position_enabled = false;
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 8d18ae68c..260b25a48 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -194,8 +194,6 @@ private:
float man_roll_max; /**< Max Roll in rad */
float man_pitch_max; /**< Max Pitch in rad */
- param_t autostart_id; /* indicates which airframe is used */
-
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -236,7 +234,6 @@ private:
param_t man_roll_max;
param_t man_pitch_max;
- param_t autostart_id; /* indicates which airframe is used */
} _parameter_handles; /**< handles for interesting parameters */
@@ -338,6 +335,9 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_actuators_0_pub(-1),
_actuators_2_pub(-1),
+ _rates_sp_id(0),
+ _actuators_id(0),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
_nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
@@ -396,19 +396,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_parameter_handles.man_roll_max = param_find("FW_MAN_R_MAX");
_parameter_handles.man_pitch_max = param_find("FW_MAN_P_MAX");
- _parameter_handles.autostart_id = param_find("SYS_AUTOSTART");
-
/* fetch initial parameter values */
parameters_update();
- // set correct uORB ID, depending on if vehicle is VTOL or not
- if (_parameters.autostart_id >= 13000 && _parameters.autostart_id <= 13999) { /* VTOL airframe?*/
- _rates_sp_id = ORB_ID(fw_virtual_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_virtual_fw);
- }
- else {
- _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_0);
- }
}
FixedwingAttitudeControl::~FixedwingAttitudeControl()
@@ -483,8 +472,6 @@ FixedwingAttitudeControl::parameters_update()
_parameters.man_roll_max = math::radians(_parameters.man_roll_max);
_parameters.man_pitch_max = math::radians(_parameters.man_pitch_max);
- param_get(_parameter_handles.autostart_id, &_parameters.autostart_id);
-
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
_pitch_ctrl.set_k_p(_parameters.p_p);
@@ -600,6 +587,16 @@ FixedwingAttitudeControl::vehicle_status_poll()
if (vehicle_status_updated) {
orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
+ /* set correct uORB ID, depending on if vehicle is VTOL or not */
+ if (!_rates_sp_id) {
+ if (_vehicle_status.is_vtol) {
+ _rates_sp_id = ORB_ID(fw_virtual_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_virtual_fw);
+ } else {
+ _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_0);
+ }
+ }
}
}
@@ -700,11 +697,11 @@ FixedwingAttitudeControl::task_main()
/* load local copies */
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
- if (_parameters.autostart_id >= 13000
- && _parameters.autostart_id <= 13999) { //vehicle type is VTOL, need to modify attitude!
- /* The following modification to the attitude is vehicle specific and in this case applies
- to tail-sitter models !!!
-
+ if (_vehicle_status.is_vtol) {
+ /* vehicle type is VTOL, need to modify attitude!
+ * The following modification to the attitude is vehicle specific and in this case applies
+ * to tail-sitter models !!!
+ *
* Since the VTOL airframe is initialized as a multicopter we need to
* modify the estimated attitude for the fixed wing operation.
* Since the neutral position of the vehicle in fixed wing mode is -90 degrees rotated around
@@ -724,22 +721,24 @@ FixedwingAttitudeControl::task_main()
R.set(_att.R);
R_adapted.set(_att.R);
- //move z to x
+ /* move z to x */
R_adapted(0, 0) = R(0, 2);
R_adapted(1, 0) = R(1, 2);
R_adapted(2, 0) = R(2, 2);
- //move x to z
+
+ /* move x to z */
R_adapted(0, 2) = R(0, 0);
R_adapted(1, 2) = R(1, 0);
R_adapted(2, 2) = R(2, 0);
- //change direction of pitch (convert to right handed system)
+ /* change direction of pitch (convert to right handed system) */
R_adapted(0, 0) = -R_adapted(0, 0);
R_adapted(1, 0) = -R_adapted(1, 0);
R_adapted(2, 0) = -R_adapted(2, 0);
math::Vector<3> euler_angles; //adapted euler angles for fixed wing operation
euler_angles = R_adapted.to_euler();
- //fill in new attitude data
+
+ /* fill in new attitude data */
_att.roll = euler_angles(0);
_att.pitch = euler_angles(1);
_att.yaw = euler_angles(2);
@@ -753,7 +752,7 @@ FixedwingAttitudeControl::task_main()
_att.R[2][1] = R_adapted(2, 1);
_att.R[2][2] = R_adapted(2, 2);
- // lastly, roll- and yawspeed have to be swaped
+ /* lastly, roll- and yawspeed have to be swaped */
float helper = _att.rollspeed;
_att.rollspeed = -_att.yawspeed;
_att.yawspeed = helper;
@@ -824,6 +823,7 @@ FixedwingAttitudeControl::task_main()
float roll_sp = _parameters.rollsp_offset_rad;
float pitch_sp = _parameters.pitchsp_offset_rad;
+ float yaw_manual = 0.0f;
float throttle_sp = 0.0f;
/* Read attitude setpoint from uorb if
@@ -849,7 +849,7 @@ FixedwingAttitudeControl::task_main()
_yaw_ctrl.reset_integrator();
}
} else if (_vcontrol_mode.flag_control_velocity_enabled) {
- /*
+ /*
* Velocity should be controlled and manual is enabled.
*/
roll_sp = (_manual.y * _parameters.man_roll_max - _parameters.trim_roll)
@@ -884,6 +884,8 @@ FixedwingAttitudeControl::task_main()
+ _parameters.rollsp_offset_rad;
pitch_sp = -(_manual.x * _parameters.man_pitch_max - _parameters.trim_pitch)
+ _parameters.pitchsp_offset_rad;
+ /* allow manual control of rudder deflection */
+ yaw_manual = _manual.r;
throttle_sp = _manual.z;
_actuators.control[4] = _manual.flaps;
@@ -983,6 +985,9 @@ FixedwingAttitudeControl::task_main()
_pitch_ctrl.get_desired_rate(),
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw;
+
+ /* add in manual rudder control */
+ _actuators.control[2] += yaw_manual;
if (!isfinite(yaw_u)) {
_yaw_ctrl.reset_integrator();
perf_count(_nonfinite_output_perf);
@@ -1022,7 +1027,7 @@ FixedwingAttitudeControl::task_main()
if (_rate_sp_pub > 0) {
/* publish the attitude rates setpoint */
orb_publish(_rates_sp_id, _rate_sp_pub, &_rates_sp);
- } else {
+ } else if (_rates_sp_id) {
/* advertise the attitude rates setpoint */
_rate_sp_pub = orb_advertise(_rates_sp_id, &_rates_sp);
}
@@ -1047,7 +1052,7 @@ FixedwingAttitudeControl::task_main()
/* publish the actuator controls */
if (_actuators_0_pub > 0) {
orb_publish(_actuators_id, _actuators_0_pub, &_actuators);
- } else {
+ } else if (_actuators_id) {
_actuators_0_pub= orb_advertise(_actuators_id, &_actuators);
}
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index e98d72afe..6f5adb5fe 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -68,6 +68,8 @@
#include <mathlib/mathlib.h>
+#include <conversion/rotation.h>
+
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
@@ -357,6 +359,9 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
/* optical flow */
mavlink_optical_flow_rad_t flow;
mavlink_msg_optical_flow_rad_decode(msg, &flow);
+
+ enum Rotation flow_rot;
+ param_get(param_find("SENS_FLOW_ROT"),&flow_rot);
struct optical_flow_s f;
memset(&f, 0, sizeof(f));
@@ -374,6 +379,10 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
f.sensor_id = flow.sensor_id;
f.gyro_temperature = flow.temperature;
+ /* rotate measurements according to parameter */
+ float zeroval = 0.0f;
+ rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zeroval);
+
if (_flow_pub < 0) {
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk
index 1cc28cce1..b46d2bd35 100644
--- a/src/modules/mavlink/mavlink_tests/module.mk
+++ b/src/modules/mavlink/mavlink_tests/module.mk
@@ -47,4 +47,6 @@ MODULE_STACKSIZE = 5000
MAXOPTIMIZATION = -Os
-EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST
+EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST -Wno-attributes -Wno-packed
+
+EXTRACFLAGS = -Wno-packed
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 0702e6378..82d2ff23a 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -126,8 +126,8 @@ private:
orb_advert_t _v_rates_sp_pub; /**< rate setpoint publication */
orb_advert_t _actuators_0_pub; /**< attitude actuator controls publication */
- orb_id_t _rates_sp_id; // pointer to correct rates setpoint uORB metadata structure
- orb_id_t _actuators_id; // pointer to correct actuator controls0 uORB metadata structure
+ orb_id_t _rates_sp_id; /**< pointer to correct rates setpoint uORB metadata structure */
+ orb_id_t _actuators_id; /**< pointer to correct actuator controls0 uORB metadata structure */
bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
@@ -175,7 +175,6 @@ private:
param_t acro_pitch_max;
param_t acro_yaw_max;
- param_t autostart_id; //what frame are we using?
} _params_handles; /**< handles for interesting parameters */
struct {
@@ -191,7 +190,6 @@ private:
float man_yaw_max;
math::Vector<3> acro_rate_max; /**< max attitude rates in acro mode */
- param_t autostart_id;
} _params;
/**
@@ -285,6 +283,8 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_att_sp_pub(-1),
_v_rates_sp_pub(-1),
_actuators_0_pub(-1),
+ _rates_sp_id(0),
+ _actuators_id(0),
_actuators_0_circuit_breaker_enabled(false),
@@ -313,8 +313,6 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params.man_yaw_max = 0.0f;
_params.acro_rate_max.zero();
- _params.autostart_id = 0; //default
-
_rates_prev.zero();
_rates_sp.zero();
_rates_int.zero();
@@ -344,19 +342,8 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params_handles.acro_pitch_max = param_find("MC_ACRO_P_MAX");
_params_handles.acro_yaw_max = param_find("MC_ACRO_Y_MAX");
- _params_handles.autostart_id = param_find("SYS_AUTOSTART");
-
/* fetch initial parameter values */
parameters_update();
- // set correct uORB ID, depending on if vehicle is VTOL or not
- if (_params.autostart_id >= 13000 && _params.autostart_id <= 13999) { /* VTOL airframe?*/
- _rates_sp_id = ORB_ID(mc_virtual_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_virtual_mc);
- }
- else {
- _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
- _actuators_id = ORB_ID(actuator_controls_0);
- }
}
MulticopterAttitudeControl::~MulticopterAttitudeControl()
@@ -440,8 +427,6 @@ MulticopterAttitudeControl::parameters_update()
_actuators_0_circuit_breaker_enabled = circuit_breaker_enabled("CBRK_RATE_CTRL", CBRK_RATE_CTRL_KEY);
- param_get(_params_handles.autostart_id, &_params.autostart_id);
-
return OK;
}
@@ -531,6 +516,16 @@ MulticopterAttitudeControl::vehicle_status_poll()
if (vehicle_status_updated) {
orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
+ /* set correct uORB ID, depending on if vehicle is VTOL or not */
+ if (!_rates_sp_id) {
+ if (_vehicle_status.is_vtol) {
+ _rates_sp_id = ORB_ID(mc_virtual_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_virtual_mc);
+ } else {
+ _rates_sp_id = ORB_ID(vehicle_rates_setpoint);
+ _actuators_id = ORB_ID(actuator_controls_0);
+ }
+ }
}
}
@@ -844,7 +839,7 @@ MulticopterAttitudeControl::task_main()
if (_v_rates_sp_pub > 0) {
orb_publish(_rates_sp_id, _v_rates_sp_pub, &_v_rates_sp);
- } else {
+ } else if (_rates_sp_id) {
_v_rates_sp_pub = orb_advertise(_rates_sp_id, &_v_rates_sp);
}
@@ -868,7 +863,7 @@ MulticopterAttitudeControl::task_main()
if (_v_rates_sp_pub > 0) {
orb_publish(_rates_sp_id, _v_rates_sp_pub, &_v_rates_sp);
- } else {
+ } else if (_rates_sp_id) {
_v_rates_sp_pub = orb_advertise(_rates_sp_id, &_v_rates_sp);
}
@@ -896,7 +891,7 @@ MulticopterAttitudeControl::task_main()
if (_actuators_0_pub > 0) {
orb_publish(_actuators_id, _actuators_0_pub, &_actuators);
- } else {
+ } else if (_actuators_id) {
_actuators_0_pub = orb_advertise(_actuators_id, &_actuators);
}
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 1f40e634e..5f8f8d02f 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -50,7 +50,8 @@
* Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).
*
* @unit meters
- * @min 0.0
+ * @min 20
+ * @max 200
* @group Mission
*/
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
@@ -61,10 +62,11 @@ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
* Default acceptance radius, overridden by acceptance radius of waypoint if set.
*
* @unit meters
- * @min 1.0
+ * @min 0.05
+ * @max 200
* @group Mission
*/
-PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
+PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f);
/**
* Set OBC mode for data link loss
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
index bfe6ce7e1..1568233b0 100644
--- a/src/modules/navigator/rtl_params.c
+++ b/src/modules/navigator/rtl_params.c
@@ -53,7 +53,8 @@
* Default value of loiter radius after RTL (fixedwing only).
*
* @unit meters
- * @min 0.0
+ * @min 20
+ * @max 200
* @group RTL
*/
PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
@@ -65,10 +66,10 @@ PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
*
* @unit meters
* @min 0
- * @max 1
+ * @max 150
* @group RTL
*/
-PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
+PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60);
/**
@@ -78,7 +79,7 @@ PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
* Land (i.e. slowly descend) from this altitude if autolanding allowed.
*
* @unit meters
- * @min 0
+ * @min 2
* @max 100
* @group RTL
*/
@@ -92,7 +93,7 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 20);
*
* @unit seconds
* @min -1
- * @max
+ * @max 300
* @group RTL
*/
PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index b78b430aa..5b047f538 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -468,7 +468,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
- LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
+ LOG_FORMAT(FLOW, "QBffffffLLHhB", "IntT,ID,RawX,RawY,RX,RY,RZ,Dist,TSpan,DtSonar,FrmCnt,GT,Qlty"),
LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
LOG_FORMAT(ESC, "HBBBHHffiffH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index fca148ec5..a065541b9 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -262,6 +262,25 @@ PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f);
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
/**
+ * PX4Flow board rotation
+ *
+ * This parameter defines the rotation of the PX4FLOW board relative to the platform.
+ * Zero rotation is defined as Y on flow board pointing towards front of vehicle
+ * Possible values are:
+ * 0 = No rotation
+ * 1 = Yaw 45°
+ * 2 = Yaw 90°
+ * 3 = Yaw 135°
+ * 4 = Yaw 180°
+ * 5 = Yaw 225°
+ * 6 = Yaw 270°
+ * 7 = Yaw 315°
+ *
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0);
+
+/**
* Board rotation Y (Pitch) offset
*
* This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 3fa1575f0..952b0447d 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -63,6 +63,7 @@
#include <drivers/drv_rc_input.h>
#include <drivers/drv_adc.h>
#include <drivers/drv_airspeed.h>
+#include <drivers/drv_px4flow.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -274,6 +275,7 @@ private:
float diff_pres_analog_scale;
int board_rotation;
+ int flow_rotation;
int external_mag_rotation;
float board_offset[3];
@@ -380,6 +382,7 @@ private:
param_t battery_current_scaling;
param_t board_rotation;
+ param_t flow_rotation;
param_t external_mag_rotation;
param_t board_offset[3];
@@ -647,6 +650,7 @@ Sensors::Sensors() :
/* rotations */
_parameter_handles.board_rotation = param_find("SENS_BOARD_ROT");
+ _parameter_handles.flow_rotation = param_find("SENS_FLOW_ROT");
_parameter_handles.external_mag_rotation = param_find("SENS_EXT_MAG_ROT");
/* rotation offsets */
@@ -871,8 +875,22 @@ Sensors::parameters_update()
}
param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));
+ param_get(_parameter_handles.flow_rotation, &(_parameters.flow_rotation));
param_get(_parameter_handles.external_mag_rotation, &(_parameters.external_mag_rotation));
+ /* set px4flow rotation */
+ int flowfd;
+ flowfd = open(PX4FLOW_DEVICE_PATH, 0);
+ if (flowfd >= 0) {
+ int flowret = ioctl(flowfd, SENSORIOCSROTATION, _parameters.flow_rotation);
+ if (flowret) {
+ warnx("flow rotation could not be set");
+ close(flowfd);
+ return ERROR;
+ }
+ close(flowfd);
+ }
+
get_rot_matrix((enum Rotation)_parameters.board_rotation, &_board_rotation);
get_rot_matrix((enum Rotation)_parameters.external_mag_rotation, &_external_mag_rotation);
@@ -890,20 +908,20 @@ Sensors::parameters_update()
/* update barometer qnh setting */
param_get(_parameter_handles.baro_qnh, &(_parameters.baro_qnh));
- int fd;
- fd = open(BARO_DEVICE_PATH, 0);
- if (fd < 0) {
+ int barofd;
+ barofd = open(BARO_DEVICE_PATH, 0);
+ if (barofd < 0) {
warn("%s", BARO_DEVICE_PATH);
errx(1, "FATAL: no barometer found");
} else {
- int ret = ioctl(fd, BAROIOCSMSLPRESSURE, (unsigned long)(_parameters.baro_qnh * 100));
- if (ret) {
+ int baroret = ioctl(barofd, BAROIOCSMSLPRESSURE, (unsigned long)(_parameters.baro_qnh * 100));
+ if (baroret) {
warnx("qnh could not be set");
- close(fd);
+ close(barofd);
return ERROR;
}
- close(fd);
+ close(barofd);
}
return OK;
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 749d00d75..b56e81e04 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -185,7 +185,11 @@ struct vehicle_status_s {
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
- bool is_rotary_wing;
+ bool is_rotary_wing; /**< True if system is in rotary wing configuration, so for a VTOL
+ this is only true while flying as a multicopter */
+ bool is_vtol; /**< True if the system is VTOL capable */
+
+ bool vtol_fw_permanent_stab; /**< True if vtol should stabilize attitude for fw in manual mode */
bool condition_battery_voltage_valid;
bool condition_system_in_air_restore; /**< true if we can restore in mid air */
diff --git a/src/modules/uORB/topics/vtol_vehicle_status.h b/src/modules/uORB/topics/vtol_vehicle_status.h
index 24ecca9fa..7b4e22bc8 100644
--- a/src/modules/uORB/topics/vtol_vehicle_status.h
+++ b/src/modules/uORB/topics/vtol_vehicle_status.h
@@ -54,6 +54,7 @@ struct vtol_vehicle_status_s {
uint64_t timestamp; /**< Microseconds since system boot */
bool vtol_in_rw_mode; /*true: vtol vehicle is in rotating wing mode */
+ bool fw_permanent_stab; /**< In fw mode stabilize attitude even if in manual mode*/
};
/**
diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp
index 9a80562f3..c72a85ecd 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -134,17 +134,21 @@ private:
struct {
param_t idle_pwm_mc; //pwm value for idle in mc mode
param_t vtol_motor_count;
+ param_t vtol_fw_permanent_stab; // in fw mode stabilize attitude also in manual mode
float mc_airspeed_min; // min airspeed in multicoper mode (including prop-wash)
float mc_airspeed_trim; // trim airspeed in multicopter mode
float mc_airspeed_max; // max airpseed in multicopter mode
+ float fw_pitch_trim; // trim for neutral elevon position in fw mode
} _params;
struct {
param_t idle_pwm_mc;
param_t vtol_motor_count;
+ param_t vtol_fw_permanent_stab;
param_t mc_airspeed_min;
param_t mc_airspeed_trim;
param_t mc_airspeed_max;
+ param_t fw_pitch_trim;
} _params_handles;
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -234,12 +238,15 @@ VtolAttitudeControl::VtolAttitudeControl() :
_params.idle_pwm_mc = PWM_LOWEST_MIN;
_params.vtol_motor_count = 0;
+ _params.vtol_fw_permanent_stab = 0;
_params_handles.idle_pwm_mc = param_find("VT_IDLE_PWM_MC");
_params_handles.vtol_motor_count = param_find("VT_MOT_COUNT");
+ _params_handles.vtol_fw_permanent_stab = param_find("VT_FW_PERM_STAB");
_params_handles.mc_airspeed_min = param_find("VT_MC_ARSPD_MIN");
_params_handles.mc_airspeed_max = param_find("VT_MC_ARSPD_MAX");
_params_handles.mc_airspeed_trim = param_find("VT_MC_ARSPD_TRIM");
+ _params_handles.fw_pitch_trim = param_find("VT_FW_PITCH_TRIM");
/* fetch initial parameter values */
parameters_update();
@@ -411,6 +418,9 @@ VtolAttitudeControl::parameters_update()
/* vtol motor count */
param_get(_params_handles.vtol_motor_count, &_params.vtol_motor_count);
+ /* vtol fw permanent stabilization */
+ param_get(_params_handles.vtol_fw_permanent_stab, &_params.vtol_fw_permanent_stab);
+
/* vtol mc mode min airspeed */
param_get(_params_handles.mc_airspeed_min, &v);
_params.mc_airspeed_min = v;
@@ -423,6 +433,10 @@ VtolAttitudeControl::parameters_update()
param_get(_params_handles.mc_airspeed_trim, &v);
_params.mc_airspeed_trim = v;
+ /* vtol pitch trim for fw mode */
+ param_get(_params_handles.fw_pitch_trim, &v);
+ _params.fw_pitch_trim = v;
+
return OK;
}
@@ -452,7 +466,7 @@ void VtolAttitudeControl::fill_fw_att_control_output()
_actuators_out_0.control[3] = _actuators_fw_in.control[3];
/*controls for the elevons */
_actuators_out_1.control[0] = -_actuators_fw_in.control[0]; // roll elevon
- _actuators_out_1.control[1] = _actuators_fw_in.control[1]; // pitch elevon
+ _actuators_out_1.control[1] = _actuators_fw_in.control[1] + _params.fw_pitch_trim; // pitch elevon
// unused now but still logged
_actuators_out_1.control[2] = _actuators_fw_in.control[2]; // yaw
_actuators_out_1.control[3] = _actuators_fw_in.control[3]; // throttle
@@ -597,6 +611,9 @@ void VtolAttitudeControl::task_main()
parameters_update(); // initialize parameter cache
+ /* update vtol vehicle status*/
+ _vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false;
+
// make sure we start with idle in mc mode
set_idle_mc();
flag_idle_mc = true;
@@ -647,6 +664,8 @@ void VtolAttitudeControl::task_main()
parameters_update();
}
+ _vtol_vehicle_status.fw_permanent_stab = _params.vtol_fw_permanent_stab == 1 ? true : false;
+
vehicle_control_mode_poll(); //Check for changes in vehicle control mode.
vehicle_manual_poll(); //Check for changes in manual inputs.
arming_status_poll(); //Check for arming status updates.
diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c
index e21bccb0c..d1d4697f3 100644
--- a/src/modules/vtol_att_control/vtol_att_control_params.c
+++ b/src/modules/vtol_att_control/vtol_att_control_params.c
@@ -86,3 +86,26 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f);
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f);
+/**
+ * Permanent stabilization in fw mode
+ *
+ * If set to one this parameter will cause permanent attitude stabilization in fw mode.
+ * This parameter has been introduced for pure convenience sake.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0);
+
+/**
+ * Fixed wing pitch trim
+ *
+ * This parameter allows to adjust the neutral elevon position in fixed wing mode.
+ *
+ * @min -1
+ * @max 1
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f);
+