aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/batt_smbus/batt_smbus.cpp540
-rw-r--r--src/drivers/batt_smbus/module.mk8
-rw-r--r--src/drivers/boards/aerocore/aerocore_led.c3
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c15
-rw-r--r--src/drivers/device/device.h7
-rw-r--r--src/drivers/device/i2c.h3
-rw-r--r--src/drivers/drv_baro.h1
-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/frsky_telemetry/frsky_telemetry.c2
-rw-r--r--src/drivers/gps/ubx.cpp19
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp253
-rw-r--r--src/drivers/hmc5883/hmc5883.h52
-rw-r--r--src/drivers/hmc5883/hmc5883_i2c.cpp175
-rw-r--r--src/drivers/hmc5883/hmc5883_spi.cpp189
-rw-r--r--src/drivers/hmc5883/module.mk4
-rw-r--r--src/drivers/hott/comms.h2
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_sensors/module.mk4
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/module.mk4
-rw-r--r--src/drivers/hott/messages.h18
-rw-r--r--src/drivers/hott/module.mk41
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp245
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp3
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp400
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp530
-rw-r--r--src/drivers/ms5611/ms5611.cpp153
-rw-r--r--src/drivers/px4flow/module.mk2
-rw-r--r--src/drivers/px4flow/px4flow.cpp35
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp2
-rw-r--r--src/drivers/sf0x/sf0x.cpp4
-rw-r--r--src/drivers/stm32/drv_hrt.c8
-rw-r--r--src/drivers/trone/trone.cpp2
-rw-r--r--src/examples/fixedwing_control/main.c2
-rw-r--r--src/examples/fixedwing_control/module.mk2
-rw-r--r--src/examples/flow_position_estimator/flow_position_estimator_main.c2
-rw-r--r--src/examples/flow_position_estimator/module.mk2
-rw-r--r--src/examples/hwtest/hwtest.c12
-rw-r--r--src/examples/matlab_csv_serial/matlab_csv_serial.c2
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c9
-rw-r--r--src/lib/conversion/rotation.cpp5
-rw-r--r--src/lib/rc/st24.c2
m---------src/lib/uavcan0
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp50
-rw-r--r--src/modules/attitude_estimator_ekf/module.mk4
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp2
-rw-r--r--src/modules/attitude_estimator_so3/module.mk2
-rw-r--r--src/modules/bottle_drop/bottle_drop.cpp7
-rw-r--r--src/modules/commander/commander.cpp72
-rw-r--r--src/modules/commander/module.mk3
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk3
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp63
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp126
-rw-r--r--src/modules/fw_pos_control_l1/module.mk2
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp2
-rw-r--r--src/modules/mavlink/mavlink_ftp.h2
-rw-r--r--src/modules/mavlink/mavlink_main.cpp7
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp4
-rw-r--r--src/modules/mavlink/mavlink_mission.cpp11
-rw-r--r--src/modules/mavlink/mavlink_parameters.cpp41
-rw-r--r--src/modules/mavlink/mavlink_parameters.h5
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp9
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk4
-rw-r--r--src/modules/mavlink/module.mk4
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp39
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp7
-rw-r--r--src/modules/navigator/datalinkloss.cpp8
-rw-r--r--src/modules/navigator/geofence.cpp17
-rw-r--r--src/modules/navigator/gpsfailure.cpp2
-rw-r--r--src/modules/navigator/mission.cpp29
-rw-r--r--src/modules/navigator/mission.h6
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator.h18
-rw-r--r--src/modules/navigator/navigator_main.cpp37
-rw-r--r--src/modules/navigator/navigator_mode.cpp2
-rw-r--r--src/modules/navigator/navigator_params.c8
-rw-r--r--src/modules/navigator/rcloss.cpp6
-rw-r--r--src/modules/navigator/rtl_params.c11
-rw-r--r--src/modules/position_estimator_inav/module.mk3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c47
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c2
-rw-r--r--src/modules/px4iofirmware/protocol.h2
-rw-r--r--src/modules/sdlog2/module.mk3
-rw-r--r--src/modules/sdlog2/sdlog2.c22
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h8
-rw-r--r--src/modules/segway/segway_main.cpp2
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c54
-rw-r--r--src/modules/sensors/sensors.cpp297
-rw-r--r--src/modules/systemlib/module.mk2
-rw-r--r--src/modules/systemlib/perf_counter.c53
-rw-r--r--src/modules/systemlib/perf_counter.h9
-rw-r--r--src/modules/systemlib/system_params.c14
-rw-r--r--src/modules/systemlib/systemlib.c2
-rw-r--r--src/modules/systemlib/systemlib.h2
-rw-r--r--src/modules/uORB/objects_common.cpp9
-rw-r--r--src/modules/uORB/topics/geofence_result.h65
-rw-r--r--src/modules/uORB/topics/mission_result.h14
-rw-r--r--src/modules/uORB/topics/rc_channels.h7
-rw-r--r--src/modules/uORB/topics/rc_parameter_map.h76
-rw-r--r--src/modules/uORB/topics/sensor_combined.h18
-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/uORB/uORB.h27
-rw-r--r--src/modules/uavcan/module.mk4
-rw-r--r--src/modules/vtol_att_control/module.mk3
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp24
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_params.c23
-rw-r--r--src/systemcmds/bl_update/bl_update.c8
-rw-r--r--src/systemcmds/mixer/module.mk3
-rw-r--r--src/systemcmds/mtd/module.mk3
-rw-r--r--src/systemcmds/param/param.c2
-rw-r--r--src/systemcmds/perf/perf.c6
-rw-r--r--src/systemcmds/tests/module.mk3
-rw-r--r--src/systemcmds/tests/test_mathlib.cpp51
120 files changed, 3491 insertions, 837 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 9d2c1441d..7f1b21a95 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 15,
1100,
ardrone_interface_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/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/boards/aerocore/aerocore_led.c b/src/drivers/boards/aerocore/aerocore_led.c
index e40d1730c..94a716029 100644
--- a/src/drivers/boards/aerocore/aerocore_led.c
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -45,6 +45,7 @@
#include "board_config.h"
#include <arch/board/board.h>
+#include <systemlib/err.h>
/*
* Ideally we'd be able to get these from up_internal.h,
@@ -54,7 +55,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index ee365e47c..2fd8bc724 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -105,6 +105,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
+#define GPIO_SPI_CS_HMC (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
@@ -119,6 +120,7 @@ __BEGIN_DECLS
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
+#define PX4_SPIDEV_HMC 5
/* External bus */
#define PX4_SPIDEV_EXT0 1
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index 8c37d31a7..27f193513 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -73,6 +73,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_configgpio(GPIO_SPI_CS_GYRO);
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
stm32_configgpio(GPIO_SPI_CS_BARO);
+ stm32_configgpio(GPIO_SPI_CS_HMC);
stm32_configgpio(GPIO_SPI_CS_MPU);
/* De-activate all peripherals,
@@ -82,6 +83,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
@@ -117,6 +119,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -125,6 +128,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -133,6 +137,16 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ break;
+
+ case PX4_SPIDEV_HMC:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, !selected);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -141,6 +155,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
break;
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index 67aaa0aff..4d4bed835 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -445,6 +445,13 @@ protected:
*/
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance);
+ /**
+ * Get the device name.
+ *
+ * @return the file system string of the device handle
+ */
+ const char* get_devname() { return _devname; }
+
bool _pub_blocked; /**< true if publishing should be blocked */
private:
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 705b398b0..8518596ea 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:
/**
@@ -132,6 +132,7 @@ protected:
*/
void set_address(uint16_t address) {
_address = address;
+ _device_id.devid_s.address = _address;
}
private:
diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h
index 248b9a73d..3e28d3d3d 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -65,6 +65,7 @@ struct baro_report {
*/
ORB_DECLARE(sensor_baro0);
ORB_DECLARE(sensor_baro1);
+ORB_DECLARE(sensor_baro2);
/*
* ioctl() definitions
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/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index bccdf1190..5035600ef 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -221,7 +221,7 @@ int frsky_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
frsky_telemetry_thread_main,
- (const char **)argv);
+ (char * const *)argv);
while (!thread_running) {
usleep(200);
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index b0eb4ab66..4563fb65c 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -808,7 +808,7 @@ UBX::payload_rx_done(void)
UBX_TRACE_RXMSG("Rx NAV-TIMEUTC\n");
{
- /* convert to unix timestamp */
+ // convert to unix timestamp
struct tm timeinfo;
timeinfo.tm_year = _buf.payload_rx_nav_timeutc.year - 1900;
timeinfo.tm_mon = _buf.payload_rx_nav_timeutc.month - 1;
@@ -818,17 +818,20 @@ UBX::payload_rx_done(void)
timeinfo.tm_sec = _buf.payload_rx_nav_timeutc.sec;
time_t epoch = mktime(&timeinfo);
-#ifndef CONFIG_RTC
- //Since we lack a hardware RTC, set the system time clock based on GPS UTC
- //TODO generalize this by moving into gps.cpp?
+ // FMUv2+ have a hardware RTC, but GPS helps us to configure it
+ // and control its drift. Since we rely on the HRT for our monotonic
+ // clock, updating it from time to time is safe.
+
+ // TODO generalize this by moving into gps.cpp?
timespec ts;
ts.tv_sec = epoch;
ts.tv_nsec = _buf.payload_rx_nav_timeutc.nano;
- clock_settime(CLOCK_REALTIME, &ts);
-#endif
+ if (clock_settime(CLOCK_REALTIME, &ts)) {
+ warn("failed setting clock");
+ }
- _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
- _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_timeutc.nano * 1e-3f);
+ _gps_position->time_gps_usec = ((uint64_t)epoch) * 1000000ULL;
+ _gps_position->time_gps_usec += _buf.payload_rx_nav_timeutc.nano / 1000;
}
_gps_position->timestamp_time = hrt_absolute_time();
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index d4dbf3778..fe70bd37f 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,7 +34,7 @@
/**
* @file hmc5883.cpp
*
- * Driver for the HMC5883 magnetometer connected via I2C.
+ * Driver for the HMC5883 / HMC5983 magnetometer connected via I2C or SPI.
*/
#include <nuttx/config.h>
@@ -74,11 +74,12 @@
#include <getopt.h>
#include <lib/conversion/rotation.h>
+#include "hmc5883.h"
+
/*
* HMC5883 internal constants and data structures.
*/
-#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
#define HMC5883L_DEVICE_PATH_INT "/dev/hmc5883_int"
#define HMC5883L_DEVICE_PATH_EXT "/dev/hmc5883_ext"
@@ -95,9 +96,6 @@
#define ADDR_DATA_OUT_Y_MSB 0x07
#define ADDR_DATA_OUT_Y_LSB 0x08
#define ADDR_STATUS 0x09
-#define ADDR_ID_A 0x0a
-#define ADDR_ID_B 0x0b
-#define ADDR_ID_C 0x0c
/* modes not changeable outside of driver */
#define HMC5883L_MODE_NORMAL (0 << 0) /* default */
@@ -115,10 +113,11 @@
#define STATUS_REG_DATA_OUT_LOCK (1 << 1) /* page 16: set if data is only partially read, read device to reset */
#define STATUS_REG_DATA_READY (1 << 0) /* page 16: set if all axes have valid measurements */
-#define ID_A_WHO_AM_I 'H'
-#define ID_B_WHO_AM_I '4'
-#define ID_C_WHO_AM_I '3'
-
+enum HMC5883_BUS {
+ HMC5883_BUS_ALL,
+ HMC5883_BUS_INTERNAL,
+ HMC5883_BUS_EXTERNAL
+};
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -130,10 +129,10 @@ static const int ERROR = -1;
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
-class HMC5883 : public device::I2C
+class HMC5883 : public device::CDev
{
public:
- HMC5883(int bus, const char *path, enum Rotation rotation);
+ HMC5883(device::Device *interface, const char *path, enum Rotation rotation);
virtual ~HMC5883();
virtual int init();
@@ -147,7 +146,7 @@ public:
void print_info();
protected:
- virtual int probe();
+ Device *_interface;
private:
work_s _work;
@@ -174,7 +173,6 @@ private:
bool _sensor_ok; /**< sensor was found and reports ok */
bool _calibrated; /**< the calibration is valid */
- int _bus; /**< the bus the device is connected to */
enum Rotation _rotation;
struct mag_report _last_report; /**< used for info() */
@@ -183,15 +181,6 @@ private:
uint8_t _conf_reg;
/**
- * Test whether the device supported by the driver is present at a
- * specific address.
- *
- * @param address The I2C bus address to probe.
- * @return True if the device is present.
- */
- int probe_address(uint8_t address);
-
- /**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
@@ -349,8 +338,9 @@ private:
extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
-HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) :
- I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000),
+HMC5883::HMC5883(device::Device *interface, const char *path, enum Rotation rotation) :
+ CDev("HMC5883", path),
+ _interface(interface),
_work{},
_measure_ticks(0),
_reports(nullptr),
@@ -369,7 +359,6 @@ HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) :
_conf_errors(perf_alloc(PC_COUNT, "hmc5883_conf_errors")),
_sensor_ok(false),
_calibrated(false),
- _bus(bus),
_rotation(rotation),
_last_report{0},
_range_bits(0),
@@ -416,9 +405,11 @@ HMC5883::init()
{
int ret = ERROR;
- /* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ ret = CDev::init();
+ if (ret != OK) {
+ debug("CDev init failed");
goto out;
+ }
/* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(mag_report));
@@ -429,20 +420,7 @@ HMC5883::init()
reset();
_class_instance = register_class_devname(MAG_DEVICE_PATH);
-
- switch (_class_instance) {
- case CLASS_DEVICE_PRIMARY:
- _mag_orb_id = ORB_ID(sensor_mag0);
- break;
-
- case CLASS_DEVICE_SECONDARY:
- _mag_orb_id = ORB_ID(sensor_mag1);
- break;
-
- case CLASS_DEVICE_TERTIARY:
- _mag_orb_id = ORB_ID(sensor_mag2);
- break;
- }
+ _mag_orb_id = ORB_ID_TRIPLE(sensor_mag, _class_instance);
ret = OK;
/* sensor is ok, but not calibrated */
@@ -559,30 +537,6 @@ void HMC5883::check_conf(void)
}
}
-int
-HMC5883::probe()
-{
- uint8_t data[3] = {0, 0, 0};
-
- _retries = 10;
-
- if (read_reg(ADDR_ID_A, data[0]) ||
- read_reg(ADDR_ID_B, data[1]) ||
- read_reg(ADDR_ID_C, data[2]))
- debug("read_reg fail");
-
- _retries = 2;
-
- if ((data[0] != ID_A_WHO_AM_I) ||
- (data[1] != ID_B_WHO_AM_I) ||
- (data[2] != ID_C_WHO_AM_I)) {
- debug("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
- return -EIO;
- }
-
- return OK;
-}
-
ssize_t
HMC5883::read(struct file *filp, char *buffer, size_t buflen)
{
@@ -643,6 +597,8 @@ HMC5883::read(struct file *filp, char *buffer, size_t buflen)
int
HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
{
+ unsigned dummy = arg;
+
switch (cmd) {
case SENSORIOCSPOLLRATE: {
switch (arg) {
@@ -768,14 +724,12 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
return check_calibration();
case MAGIOCGEXTERNAL:
- if (_bus == PX4_I2C_BUS_EXPANSION)
- return 1;
- else
- return 0;
+ debug("MAGIOCGEXTERNAL in main driver");
+ return _interface->ioctl(cmd, dummy);
default:
/* give it to the superclass */
- return I2C::ioctl(filp, cmd, arg);
+ return CDev::ioctl(filp, cmd, arg);
}
}
@@ -890,7 +844,6 @@ HMC5883::collect()
} report;
int ret;
- uint8_t cmd;
uint8_t check_counter;
perf_begin(_sample_perf);
@@ -908,8 +861,7 @@ HMC5883::collect()
*/
/* get measurements from the device */
- cmd = ADDR_DATA_OUT_X_MSB;
- ret = transfer(&cmd, 1, (uint8_t *)&hmc_report, sizeof(hmc_report));
+ ret = _interface->read(ADDR_DATA_OUT_X_MSB, (uint8_t *)&hmc_report, sizeof(hmc_report));
if (ret != OK) {
perf_count(_comms_errors);
@@ -946,14 +898,14 @@ HMC5883::collect()
/* scale values for output */
-#ifdef PX4_I2C_BUS_ONBOARD
- if (_bus == PX4_I2C_BUS_ONBOARD) {
+ // XXX revisit for SPI part, might require a bus type IOCTL
+ unsigned dummy;
+ if (!_interface->ioctl(MAGIOCGEXTERNAL, dummy)) {
// convert onboard so it matches offboard for the
// scaling below
report.y = -report.y;
report.x = -report.x;
}
-#endif
/* the standard external mag by 3DR has x pointing to the
* right, y pointing backwards, and z down, therefore switch x
@@ -1291,15 +1243,17 @@ int HMC5883::set_excitement(unsigned enable)
int
HMC5883::write_reg(uint8_t reg, uint8_t val)
{
- uint8_t cmd[] = { reg, val };
-
- return transfer(&cmd[0], 2, nullptr, 0);
+ uint8_t buf = val;
+ return _interface->write(reg, &buf, 1);
}
int
HMC5883::read_reg(uint8_t reg, uint8_t &val)
{
- return transfer(&reg, 1, &val, 1);
+ uint8_t buf = val;
+ int ret = _interface->read(reg, &buf, 1);
+ val = buf;
+ return ret;
}
float
@@ -1351,6 +1305,7 @@ void test(int bus);
void reset(int bus);
int info(int bus);
int calibrate(int bus);
+const char* get_path(int bus);
void usage();
/**
@@ -1360,43 +1315,99 @@ void usage();
* is either successfully up and running or failed to start.
*/
void
-start(int bus, enum Rotation rotation)
+start(int external_bus, enum Rotation rotation)
{
int fd;
/* create the driver, attempt expansion bus first */
- if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
- if (g_dev_ext != nullptr)
- errx(0, "already started external");
- g_dev_ext = new HMC5883(PX4_I2C_BUS_EXPANSION, HMC5883L_DEVICE_PATH_EXT, rotation);
- if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
- delete g_dev_ext;
- g_dev_ext = nullptr;
+ if (g_dev_ext != nullptr) {
+ warnx("already started external");
+ } else if (external_bus == HMC5883_BUS_ALL || external_bus == HMC5883_BUS_EXTERNAL) {
+
+ device::Device *interface = nullptr;
+
+ /* create the driver, only attempt I2C for the external bus */
+ if (interface == nullptr && (HMC5883_I2C_interface != nullptr)) {
+ interface = HMC5883_I2C_interface(PX4_I2C_BUS_EXPANSION);
+
+ if (interface->init() != OK) {
+ delete interface;
+ interface = nullptr;
+ warnx("no device on I2C bus #%u", PX4_I2C_BUS_EXPANSION);
+ }
+ }
+
+#ifdef PX4_I2C_BUS_ONBOARD
+ if (interface == nullptr && (HMC5883_I2C_interface != nullptr)) {
+ interface = HMC5883_I2C_interface(PX4_I2C_BUS_ONBOARD);
+
+ if (interface->init() != OK) {
+ delete interface;
+ interface = nullptr;
+ warnx("no device on I2C bus #%u", PX4_I2C_BUS_ONBOARD);
+ }
+ }
+#endif
+
+ /* interface will be null if init failed */
+ if (interface != nullptr) {
+
+ g_dev_ext = new HMC5883(interface, HMC5883L_DEVICE_PATH_EXT, rotation);
+ if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
+
}
}
-#ifdef PX4_I2C_BUS_ONBOARD
/* if this failed, attempt onboard sensor */
- if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) {
- if (g_dev_int != nullptr)
- errx(0, "already started internal");
- g_dev_int = new HMC5883(PX4_I2C_BUS_ONBOARD, HMC5883L_DEVICE_PATH_INT, rotation);
- if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+ if (g_dev_int != nullptr) {
+ warnx("already started internal");
+ } else if (external_bus == HMC5883_BUS_ALL || external_bus == HMC5883_BUS_INTERNAL) {
- /* tear down the failing onboard instance */
- delete g_dev_int;
- g_dev_int = nullptr;
+ device::Device *interface = nullptr;
- if (bus == PX4_I2C_BUS_ONBOARD) {
- goto fail;
- }
+ /* create the driver, try SPI first, fall back to I2C if unsuccessful */
+#ifdef PX4_SPIDEV_HMC
+ if (HMC5883_SPI_interface != nullptr) {
+ interface = HMC5883_SPI_interface(PX4_SPI_BUS_SENSORS);
}
- if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) {
+#endif
+
+#ifdef PX4_I2C_BUS_ONBOARD
+ /* this device is already connected as external if present above */
+ if (interface == nullptr && (HMC5883_I2C_interface != nullptr)) {
+ interface = HMC5883_I2C_interface(PX4_I2C_BUS_ONBOARD);
+ }
+#endif
+ if (interface == nullptr) {
+ warnx("no internal bus scanned");
goto fail;
}
+
+ if (interface->init() != OK) {
+ delete interface;
+ warnx("no device on internal bus");
+ } else {
+
+ g_dev_int = new HMC5883(interface, HMC5883L_DEVICE_PATH_INT, rotation);
+ if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+
+ /* tear down the failing onboard instance */
+ delete g_dev_int;
+ g_dev_int = nullptr;
+
+ if (external_bus == HMC5883_BUS_INTERNAL) {
+ goto fail;
+ }
+ }
+ if (g_dev_int == nullptr && external_bus == HMC5883_BUS_INTERNAL) {
+ goto fail;
+ }
+ }
}
-#endif
if (g_dev_int == nullptr && g_dev_ext == nullptr)
goto fail;
@@ -1425,11 +1436,11 @@ start(int bus, enum Rotation rotation)
exit(0);
fail:
- if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) {
+ if (g_dev_int != nullptr && (external_bus == HMC5883_BUS_ALL || external_bus == HMC5883_BUS_INTERNAL)) {
delete g_dev_int;
g_dev_int = nullptr;
}
- if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) {
+ if (g_dev_ext != nullptr && (external_bus == HMC5883_BUS_ALL || external_bus == HMC5883_BUS_EXTERNAL)) {
delete g_dev_ext;
g_dev_ext = nullptr;
}
@@ -1448,7 +1459,7 @@ test(int bus)
struct mag_report report;
ssize_t sz;
int ret;
- const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
+ const char *path = get_path(bus);
int fd = open(path, O_RDONLY);
@@ -1549,7 +1560,7 @@ test(int bus)
int calibrate(int bus)
{
int ret;
- const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
+ const char *path = get_path(bus);
int fd = open(path, O_RDONLY);
@@ -1576,7 +1587,7 @@ int calibrate(int bus)
void
reset(int bus)
{
- const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
+ const char *path = get_path(bus);
int fd = open(path, O_RDONLY);
@@ -1600,12 +1611,12 @@ info(int bus)
{
int ret = 1;
- HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD ? g_dev_int : g_dev_ext);
+ HMC5883 *g_dev = (bus == HMC5883_BUS_INTERNAL ? g_dev_int : g_dev_ext);
if (g_dev == nullptr) {
warnx("not running on bus %d", bus);
} else {
- warnx("running on bus: %d (%s)\n", bus, ((PX4_I2C_BUS_ONBOARD) ? "onboard" : "offboard"));
+ warnx("running on bus: %d (%s)\n", bus, ((HMC5883_BUS_INTERNAL) ? "onboard" : "offboard"));
g_dev->print_info();
ret = 0;
@@ -1614,6 +1625,12 @@ info(int bus)
return ret;
}
+const char*
+get_path(int bus)
+{
+ return ((bus == HMC5883_BUS_INTERNAL) ? HMC5883L_DEVICE_PATH_INT : HMC5883L_DEVICE_PATH_EXT);
+}
+
void
usage()
{
@@ -1622,7 +1639,7 @@ usage()
warnx(" -R rotation");
warnx(" -C calibrate on start");
warnx(" -X only external bus");
-#ifdef PX4_I2C_BUS_ONBOARD
+#if (PX4_I2C_BUS_ONBOARD || PX4_SPIDEV_HMC)
warnx(" -I only internal bus");
#endif
}
@@ -1633,7 +1650,7 @@ int
hmc5883_main(int argc, char *argv[])
{
int ch;
- int bus = -1;
+ int bus = HMC5883_BUS_ALL;
enum Rotation rotation = ROTATION_NONE;
bool calibrate = false;
@@ -1642,13 +1659,13 @@ hmc5883_main(int argc, char *argv[])
case 'R':
rotation = (enum Rotation)atoi(optarg);
break;
-#ifdef PX4_I2C_BUS_ONBOARD
+#if (PX4_I2C_BUS_ONBOARD || PX4_SPIDEV_HMC)
case 'I':
- bus = PX4_I2C_BUS_ONBOARD;
+ bus = HMC5883_BUS_INTERNAL;
break;
#endif
case 'X':
- bus = PX4_I2C_BUS_EXPANSION;
+ bus = HMC5883_BUS_EXTERNAL;
break;
case 'C':
calibrate = true;
@@ -1692,13 +1709,13 @@ hmc5883_main(int argc, char *argv[])
* Print driver information.
*/
if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
- if (bus == -1) {
+ if (bus == HMC5883_BUS_ALL) {
int ret = 0;
- if (hmc5883::info(PX4_I2C_BUS_ONBOARD)) {
+ if (hmc5883::info(HMC5883_BUS_INTERNAL)) {
ret = 1;
}
- if (hmc5883::info(PX4_I2C_BUS_EXPANSION)) {
+ if (hmc5883::info(HMC5883_BUS_EXTERNAL)) {
ret = 1;
}
exit(ret);
diff --git a/src/drivers/hmc5883/hmc5883.h b/src/drivers/hmc5883/hmc5883.h
new file mode 100644
index 000000000..0eb773629
--- /dev/null
+++ b/src/drivers/hmc5883/hmc5883.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 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 hmc5883.h
+ *
+ * Shared defines for the hmc5883 driver.
+ */
+
+#pragma once
+
+#define ADDR_ID_A 0x0a
+#define ADDR_ID_B 0x0b
+#define ADDR_ID_C 0x0c
+
+#define ID_A_WHO_AM_I 'H'
+#define ID_B_WHO_AM_I '4'
+#define ID_C_WHO_AM_I '3'
+
+/* interface factories */
+extern device::Device *HMC5883_SPI_interface(int bus) weak_function;
+extern device::Device *HMC5883_I2C_interface(int bus) weak_function;
diff --git a/src/drivers/hmc5883/hmc5883_i2c.cpp b/src/drivers/hmc5883/hmc5883_i2c.cpp
new file mode 100644
index 000000000..782ea62fe
--- /dev/null
+++ b/src/drivers/hmc5883/hmc5883_i2c.cpp
@@ -0,0 +1,175 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 HMC5883_I2C.cpp
+ *
+ * I2C interface for HMC5883 / HMC 5983
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/i2c.h>
+#include <drivers/drv_mag.h>
+
+#include "hmc5883.h"
+
+#include "board_config.h"
+
+#ifdef PX4_I2C_OBDEV_HMC5883
+
+#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
+
+device::Device *HMC5883_I2C_interface(int bus);
+
+class HMC5883_I2C : public device::I2C
+{
+public:
+ HMC5883_I2C(int bus);
+ virtual ~HMC5883_I2C();
+
+ virtual int init();
+ virtual int read(unsigned address, void *data, unsigned count);
+ virtual int write(unsigned address, void *data, unsigned count);
+
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+protected:
+ virtual int probe();
+
+};
+
+device::Device *
+HMC5883_I2C_interface(int bus)
+{
+ return new HMC5883_I2C(bus);
+}
+
+HMC5883_I2C::HMC5883_I2C(int bus) :
+ I2C("HMC5883_I2C", nullptr, bus, HMC5883L_ADDRESS, 400000)
+{
+}
+
+HMC5883_I2C::~HMC5883_I2C()
+{
+}
+
+int
+HMC5883_I2C::init()
+{
+ /* this will call probe() */
+ return I2C::init();
+}
+
+int
+HMC5883_I2C::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+
+ case MAGIOCGEXTERNAL:
+ if (_bus == PX4_I2C_BUS_EXPANSION) {
+ return 1;
+ } else {
+ return 0;
+ }
+
+ default:
+ ret = -EINVAL;
+ }
+
+ return ret;
+}
+
+int
+HMC5883_I2C::probe()
+{
+ uint8_t data[3] = {0, 0, 0};
+
+ _retries = 10;
+
+ if (read(ADDR_ID_A, &data[0], 1) ||
+ read(ADDR_ID_B, &data[1], 1) ||
+ read(ADDR_ID_C, &data[2], 1)) {
+ debug("read_reg fail");
+ return -EIO;
+ }
+
+ _retries = 2;
+
+ if ((data[0] != ID_A_WHO_AM_I) ||
+ (data[1] != ID_B_WHO_AM_I) ||
+ (data[2] != ID_C_WHO_AM_I)) {
+ debug("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
+ return -EIO;
+ }
+
+ return OK;
+}
+
+int
+HMC5883_I2C::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t buf[32];
+
+ if (sizeof(buf) < (count + 1)) {
+ return -EIO;
+ }
+
+ buf[0] = address;
+ memcpy(&buf[1], data, count);
+
+ return transfer(&buf[0], count + 1, nullptr, 0);
+}
+
+int
+HMC5883_I2C::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t cmd = address;
+ return transfer(&cmd, 1, (uint8_t *)data, count);
+}
+
+#endif /* PX4_I2C_OBDEV_HMC5883 */
diff --git a/src/drivers/hmc5883/hmc5883_spi.cpp b/src/drivers/hmc5883/hmc5883_spi.cpp
new file mode 100644
index 000000000..25a2f2b40
--- /dev/null
+++ b/src/drivers/hmc5883/hmc5883_spi.cpp
@@ -0,0 +1,189 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 HMC5883_SPI.cpp
+ *
+ * SPI interface for HMC5983
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/spi.h>
+#include <drivers/drv_mag.h>
+
+#include "hmc5883.h"
+#include <board_config.h>
+
+#ifdef PX4_SPIDEV_HMC
+
+/* SPI protocol address bits */
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define HMC_MAX_SEND_LEN 4
+#define HMC_MAX_RCV_LEN 8
+
+device::Device *HMC5883_SPI_interface(int bus);
+
+class HMC5883_SPI : public device::SPI
+{
+public:
+ HMC5883_SPI(int bus, spi_dev_e device);
+ virtual ~HMC5883_SPI();
+
+ virtual int init();
+ virtual int read(unsigned address, void *data, unsigned count);
+ virtual int write(unsigned address, void *data, unsigned count);
+
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+};
+
+device::Device *
+HMC5883_SPI_interface(int bus)
+{
+ return new HMC5883_SPI(bus, (spi_dev_e)PX4_SPIDEV_HMC);
+}
+
+HMC5883_SPI::HMC5883_SPI(int bus, spi_dev_e device) :
+ SPI("HMC5883_SPI", nullptr, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz */)
+{
+}
+
+HMC5883_SPI::~HMC5883_SPI()
+{
+}
+
+int
+HMC5883_SPI::init()
+{
+ int ret;
+
+ ret = SPI::init();
+ if (ret != OK) {
+ debug("SPI init failed");
+ return -EIO;
+ }
+
+ // read WHO_AM_I value
+ uint8_t data[3] = {0, 0, 0};
+
+ if (read(ADDR_ID_A, &data[0], 1) ||
+ read(ADDR_ID_B, &data[1], 1) ||
+ read(ADDR_ID_C, &data[2], 1)) {
+ debug("read_reg fail");
+ }
+
+ if ((data[0] != ID_A_WHO_AM_I) ||
+ (data[1] != ID_B_WHO_AM_I) ||
+ (data[2] != ID_C_WHO_AM_I)) {
+ debug("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
+ return -EIO;
+ }
+
+ return OK;
+}
+
+int
+HMC5883_SPI::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+
+ case MAGIOCGEXTERNAL:
+
+#ifdef PX4_SPI_BUS_EXT
+ if (_bus == PX4_SPI_BUS_EXT) {
+ return 1;
+ } else
+#endif
+ {
+ return 0;
+ }
+
+ default:
+ {
+ ret = -EINVAL;
+ }
+ }
+
+ return ret;
+}
+
+int
+HMC5883_SPI::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t buf[32];
+
+ if (sizeof(buf) < (count + 1)) {
+ return -EIO;
+ }
+
+ buf[0] = address | DIR_WRITE;
+ memcpy(&buf[1], data, count);
+
+ return transfer(&buf[0], &buf[0], count + 1);
+}
+
+int
+HMC5883_SPI::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t buf[32];
+
+ if (sizeof(buf) < (count + 1)) {
+ return -EIO;
+ }
+
+ buf[0] = address | DIR_READ | ADDR_INCREMENT;
+
+ int ret = transfer(&buf[0], &buf[0], count + 1);
+ memcpy(data, &buf[1], count);
+ return ret;
+}
+
+#endif /* PX4_SPIDEV_HMC */
diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk
index be2ee7276..d4028b511 100644
--- a/src/drivers/hmc5883/module.mk
+++ b/src/drivers/hmc5883/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -37,7 +37,7 @@
MODULE_COMMAND = hmc5883
-SRCS = hmc5883.cpp
+SRCS = hmc5883_i2c.cpp hmc5883_spi.cpp hmc5883.cpp
MODULE_STACKSIZE = 1200
diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h
index f5608122f..0a586a8fd 100644
--- a/src/drivers/hott/comms.h
+++ b/src/drivers/hott/comms.h
@@ -41,6 +41,6 @@
#ifndef COMMS_H_
#define COMMS_H
-int open_uart(const char *device);
+__EXPORT int open_uart(const char *device);
#endif /* COMMS_H_ */
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index 8ab9d8d55..4b8e0c0b0 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -214,7 +214,7 @@ hott_sensors_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
1024,
hott_sensors_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk
index 47aea6caf..25a6f0ac0 100644
--- a/src/drivers/hott/hott_sensors/module.mk
+++ b/src/drivers/hott/hott_sensors/module.mk
@@ -37,8 +37,6 @@
MODULE_COMMAND = hott_sensors
-SRCS = hott_sensors.cpp \
- ../messages.cpp \
- ../comms.cpp
+SRCS = hott_sensors.cpp
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index edbb14172..17a24d104 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -240,7 +240,7 @@ hott_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk
index cd7bdbc85..9de47b356 100644
--- a/src/drivers/hott/hott_telemetry/module.mk
+++ b/src/drivers/hott/hott_telemetry/module.mk
@@ -37,8 +37,6 @@
MODULE_COMMAND = hott_telemetry
-SRCS = hott_telemetry.cpp \
- ../messages.cpp \
- ../comms.cpp
+SRCS = hott_telemetry.cpp
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h
index 224f8fc56..a116a50dd 100644
--- a/src/drivers/hott/messages.h
+++ b/src/drivers/hott/messages.h
@@ -235,15 +235,15 @@ struct gps_module_msg {
// The maximum size of a message.
#define MAX_MESSAGE_BUFFER_SIZE 45
-void init_sub_messages(void);
-void init_pub_messages(void);
-void build_gam_request(uint8_t *buffer, size_t *size);
-void publish_gam_message(const uint8_t *buffer);
-void build_eam_response(uint8_t *buffer, size_t *size);
-void build_gam_response(uint8_t *buffer, size_t *size);
-void build_gps_response(uint8_t *buffer, size_t *size);
-float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
+__EXPORT void init_sub_messages(void);
+__EXPORT void init_pub_messages(void);
+__EXPORT void build_gam_request(uint8_t *buffer, size_t *size);
+__EXPORT void publish_gam_message(const uint8_t *buffer);
+__EXPORT void build_eam_response(uint8_t *buffer, size_t *size);
+__EXPORT void build_gam_response(uint8_t *buffer, size_t *size);
+__EXPORT void build_gps_response(uint8_t *buffer, size_t *size);
+__EXPORT float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+__EXPORT void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
#endif /* MESSAGES_H_ */
diff --git a/src/drivers/hott/module.mk b/src/drivers/hott/module.mk
new file mode 100644
index 000000000..31a66d491
--- /dev/null
+++ b/src/drivers/hott/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Graupner HoTT Sensors messages.
+#
+
+SRCS = messages.cpp \
+ comms.cpp
+
+MAXOPTIMIZATION = -Os
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..57754e4c0 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,30 @@ 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;
+ perf_counter_t _bad_values;
+
+ 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;
+ // values used to
+ float _last_accel[3];
+ uint8_t _constant_accel_count;
+
+ // 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 +348,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 +404,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 +472,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 +545,16 @@ 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")),
+ _bad_values(perf_alloc(PC_COUNT, "lsm303d_bad_values")),
+ _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),
+ _constant_accel_count(0),
+ _checked_next(0)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D;
@@ -586,9 +596,8 @@ 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(_bad_values);
perf_free(_accel_reschedules);
}
@@ -703,15 +712,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 +747,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 +773,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 +1154,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 +1172,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 +1341,6 @@ LSM303D::accel_set_samplerate(unsigned frequency)
}
modify_reg(ADDR_CTRL_REG1, clearbits, setbits);
- _reg1_expected = (_reg1_expected & ~clearbits) | setbits;
return OK;
}
@@ -1515,24 +1416,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 +1462,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 +1508,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
+ // register reads and bad values. 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) + perf_event_count(_bad_values);
accel_report.x_raw = raw_accel_report.x;
accel_report.y_raw = raw_accel_report.y;
@@ -1582,6 +1523,36 @@ LSM303D::measure()
float y_in_new = ((accel_report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
float z_in_new = ((accel_report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+ /*
+ we have logs where the accelerometers get stuck at a fixed
+ large value. We want to detect this and mark the sensor as
+ being faulty
+ */
+ if (fabsf(_last_accel[0] - x_in_new) < 0.001f &&
+ fabsf(_last_accel[1] - y_in_new) < 0.001f &&
+ fabsf(_last_accel[2] - z_in_new) < 0.001f &&
+ fabsf(x_in_new) > 20 &&
+ fabsf(y_in_new) > 20 &&
+ fabsf(z_in_new) > 20) {
+ _constant_accel_count += 1;
+ } else {
+ _constant_accel_count = 0;
+ }
+ if (_constant_accel_count > 100) {
+ // we've had 100 constant accel readings with large
+ // values. The sensor is almost certainly dead. We
+ // will raise the error_count so that the top level
+ // flight code will know to avoid this sensor, but
+ // we'll still give the data so that it can be logged
+ // and viewed
+ perf_count(_bad_values);
+ _constant_accel_count = 0;
+ }
+
+ _last_accel[0] = x_in_new;
+ _last_accel[1] = y_in_new;
+ _last_accel[2] = z_in_new;
+
accel_report.x = _accel_filter_x.apply(x_in_new);
accel_report.y = _accel_filter_y.apply(y_in_new);
accel_report.z = _accel_filter_z.apply(z_in_new);
@@ -1611,12 +1582,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 +1656,22 @@ 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(_bad_values);
+ 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 +1729,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 +1811,8 @@ void test();
void reset();
void info();
void regdump();
-void logging();
void usage();
+void test_error();
/**
* Start the driver.
@@ -2047,15 +2019,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 +2035,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 +2099,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 a95e041a1..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
@@ -194,6 +201,18 @@ public:
*/
void print_info();
+ 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();
@@ -229,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;
@@ -240,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.
*/
@@ -255,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
@@ -279,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);
/**
@@ -302,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.
@@ -345,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.
*/
@@ -405,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;
@@ -458,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);
}
@@ -484,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;
@@ -569,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);
@@ -603,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
@@ -622,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:
@@ -637,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;
}
@@ -649,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
@@ -682,6 +786,7 @@ MPU6000::probe()
case MPU6000_REV_D9:
case MPU6000_REV_D10:
debug("ID 0x%02x", _product);
+ _checked_values[0] = _product;
return OK;
}
@@ -698,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;
}
@@ -732,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
@@ -831,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)
{
@@ -872,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) {
@@ -1092,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));
@@ -1142,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)
{
@@ -1214,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;
@@ -1252,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);
@@ -1290,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;
+ }
/*
@@ -1319,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.
@@ -1409,11 +1751,38 @@ 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
+MPU6000::print_registers()
+{
+ printf("MPU6000 registers\n");
+ for (uint8_t reg=MPUREG_PRODUCT_ID; reg<=108; reg++) {
+ uint8_t v = read_reg(reg);
+ printf("%02x:%02x ",(unsigned)reg, (unsigned)v);
+ if ((reg - (MPUREG_PRODUCT_ID-1)) % 13 == 0) {
+ printf("\n");
+ }
+ }
+ printf("\n");
}
+
MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) :
CDev("MPU6000_gyro", path),
_parent(parent),
@@ -1479,6 +1848,9 @@ void start(bool, enum Rotation);
void test(bool);
void reset(bool);
void info(bool);
+void regdump(bool);
+void testerror(bool);
+void factorytest(bool);
void usage();
/**
@@ -1654,10 +2026,56 @@ info(bool external_bus)
exit(0);
}
+/**
+ * Dump the register information
+ */
+void
+regdump(bool external_bus)
+{
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
+ errx(1, "driver not running");
+
+ printf("regdump @ %p\n", *g_dev_ptr);
+ (*g_dev_ptr)->print_registers();
+
+ exit(0);
+}
+
+/**
+ * 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'");
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'factorytest', 'testerror'");
warnx("options:");
warnx(" -X (external bus)");
warnx(" -R rotation");
@@ -1714,5 +2132,17 @@ mpu6000_main(int argc, char *argv[])
if (!strcmp(verb, "info"))
mpu6000::info(external_bus);
- errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+ /*
+ * Print register information.
+ */
+ if (!strcmp(verb, "regdump"))
+ mpu6000::regdump(external_bus);
+
+ 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/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 889643d0d..0a793cbc9 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -91,12 +91,13 @@ static const int ERROR = -1;
/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
-#define MS5611_BARO_DEVICE_PATH "/dev/ms5611"
+#define MS5611_BARO_DEVICE_PATH_EXT "/dev/ms5611_ext"
+#define MS5611_BARO_DEVICE_PATH_INT "/dev/ms5611_int"
class MS5611 : public device::CDev
{
public:
- MS5611(device::Device *interface, ms5611::prom_u &prom_buf);
+ MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char* path);
~MS5611();
virtual int init();
@@ -133,6 +134,7 @@ protected:
unsigned _msl_pressure; /* in Pa */
orb_advert_t _baro_topic;
+ orb_id_t _orb_id;
int _class_instance;
@@ -195,8 +197,8 @@ protected:
*/
extern "C" __EXPORT int ms5611_main(int argc, char *argv[]);
-MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf) :
- CDev("MS5611", MS5611_BARO_DEVICE_PATH),
+MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char* path) :
+ CDev("MS5611", path),
_interface(interface),
_prom(prom_buf.s),
_measure_ticks(0),
@@ -224,7 +226,7 @@ MS5611::~MS5611()
stop_cycle();
if (_class_instance != -1)
- unregister_class_devname(MS5611_BARO_DEVICE_PATH, _class_instance);
+ unregister_class_devname(get_devname(), _class_instance);
/* free any existing reports */
if (_reports != nullptr)
@@ -261,6 +263,7 @@ MS5611::init()
/* register alternate interfaces if we have to */
_class_instance = register_class_devname(BARO_DEVICE_PATH);
+ _orb_id = ORB_ID_TRIPLE(sensor_baro, _class_instance);
struct baro_report brp;
/* do a first measurement cycle to populate reports with valid data */
@@ -300,14 +303,7 @@ MS5611::init()
ret = OK;
- switch (_class_instance) {
- case CLASS_DEVICE_PRIMARY:
- _baro_topic = orb_advertise(ORB_ID(sensor_baro0), &brp);
- break;
- case CLASS_DEVICE_SECONDARY:
- _baro_topic = orb_advertise(ORB_ID(sensor_baro1), &brp);
- break;
- }
+ _baro_topic = orb_advertise(_orb_id, &brp);
if (_baro_topic < 0) {
warnx("failed to create sensor_baro publication");
@@ -729,15 +725,7 @@ MS5611::collect()
/* publish it */
if (!(_pub_blocked)) {
/* publish it */
- switch (_class_instance) {
- case CLASS_DEVICE_PRIMARY:
- orb_publish(ORB_ID(sensor_baro0), _baro_topic, &report);
- break;
-
- case CLASS_DEVICE_SECONDARY:
- orb_publish(ORB_ID(sensor_baro1), _baro_topic, &report);
- break;
- }
+ orb_publish(_orb_id, _baro_topic, &report);
}
if (_reports->force(&report)) {
@@ -787,13 +775,15 @@ MS5611::print_info()
namespace ms5611
{
-MS5611 *g_dev;
+/* initialize explicitely for clarity */
+MS5611 *g_dev_ext = nullptr;
+MS5611 *g_dev_int = nullptr;
void start(bool external_bus);
-void test();
-void reset();
+void test(bool external_bus);
+void reset(bool external_bus);
void info();
-void calibrate(unsigned altitude);
+void calibrate(unsigned altitude, bool external_bus);
void usage();
/**
@@ -852,9 +842,13 @@ start(bool external_bus)
int fd;
prom_u prom_buf;
- if (g_dev != nullptr)
+ if (external_bus && (g_dev_ext != nullptr)) {
+ /* if already started, the still command succeeded */
+ errx(0, "ext already started");
+ } else if (!external_bus && (g_dev_int != nullptr)) {
/* if already started, the still command succeeded */
- errx(0, "already started");
+ errx(0, "int already started");
+ }
device::Device *interface = nullptr;
@@ -872,16 +866,35 @@ start(bool external_bus)
errx(1, "interface init failed");
}
- g_dev = new MS5611(interface, prom_buf);
- if (g_dev == nullptr) {
- delete interface;
- errx(1, "failed to allocate driver");
+ if (external_bus) {
+ g_dev_ext = new MS5611(interface, prom_buf, MS5611_BARO_DEVICE_PATH_EXT);
+ if (g_dev_ext == nullptr) {
+ delete interface;
+ errx(1, "failed to allocate driver");
+ }
+
+ if (g_dev_ext->init() != OK)
+ goto fail;
+
+ fd = open(MS5611_BARO_DEVICE_PATH_EXT, O_RDONLY);
+
+ } else {
+
+ g_dev_int = new MS5611(interface, prom_buf, MS5611_BARO_DEVICE_PATH_INT);
+ if (g_dev_int == nullptr) {
+ delete interface;
+ errx(1, "failed to allocate driver");
+ }
+
+ if (g_dev_int->init() != OK)
+ goto fail;
+
+ fd = open(MS5611_BARO_DEVICE_PATH_INT, O_RDONLY);
+
}
- if (g_dev->init() != OK)
- goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
+
if (fd < 0) {
warnx("can't open baro device");
goto fail;
@@ -895,9 +908,14 @@ start(bool external_bus)
fail:
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (g_dev_int != nullptr) {
+ delete g_dev_int;
+ g_dev_int = nullptr;
+ }
+
+ if (g_dev_ext != nullptr) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
}
errx(1, "driver start failed");
@@ -909,16 +927,22 @@ fail:
* and automatic modes.
*/
void
-test()
+test(bool external_bus)
{
struct baro_report report;
ssize_t sz;
int ret;
- int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
+ int fd;
+
+ if (external_bus) {
+ fd = open(MS5611_BARO_DEVICE_PATH_EXT, O_RDONLY);
+ } else {
+ fd = open(MS5611_BARO_DEVICE_PATH_INT, O_RDONLY);
+ }
if (fd < 0)
- err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH);
+ err(1, "open failed (try 'ms5611 start' if the driver is not running)");
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -972,9 +996,15 @@ test()
* Reset the driver.
*/
void
-reset()
+reset(bool external_bus)
{
- int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
+ int fd;
+
+ if (external_bus) {
+ fd = open(MS5611_BARO_DEVICE_PATH_EXT, O_RDONLY);
+ } else {
+ fd = open(MS5611_BARO_DEVICE_PATH_INT, O_RDONLY);
+ }
if (fd < 0)
err(1, "failed ");
@@ -994,11 +1024,18 @@ reset()
void
info()
{
- if (g_dev == nullptr)
+ if (g_dev_ext == nullptr && g_dev_int == nullptr)
errx(1, "driver not running");
- printf("state @ %p\n", g_dev);
- g_dev->print_info();
+ if (g_dev_ext) {
+ warnx("ext:");
+ g_dev_ext->print_info();
+ }
+
+ if (g_dev_int) {
+ warnx("int:");
+ g_dev_int->print_info();
+ }
exit(0);
}
@@ -1007,16 +1044,22 @@ info()
* Calculate actual MSL pressure given current altitude
*/
void
-calibrate(unsigned altitude)
+calibrate(unsigned altitude, bool external_bus)
{
struct baro_report report;
float pressure;
float p1;
- int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY);
+ int fd;
+
+ if (external_bus) {
+ fd = open(MS5611_BARO_DEVICE_PATH_EXT, O_RDONLY);
+ } else {
+ fd = open(MS5611_BARO_DEVICE_PATH_INT, O_RDONLY);
+ }
if (fd < 0)
- err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH);
+ err(1, "open failed (try 'ms5611 start' if the driver is not running)");
/* start the sensor polling at max */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX))
@@ -1101,6 +1144,12 @@ ms5611_main(int argc, char *argv[])
const char *verb = argv[optind];
+ if (argc > optind+1) {
+ if (!strcmp(argv[optind+1], "-X")) {
+ external_bus = true;
+ }
+ }
+
/*
* Start/load the driver.
*/
@@ -1111,13 +1160,13 @@ ms5611_main(int argc, char *argv[])
* Test the driver/device.
*/
if (!strcmp(verb, "test"))
- ms5611::test();
+ ms5611::test(external_bus);
/*
* Reset the driver.
*/
if (!strcmp(verb, "reset"))
- ms5611::reset();
+ ms5611::reset(external_bus);
/*
* Print driver information.
@@ -1134,7 +1183,7 @@ ms5611_main(int argc, char *argv[])
long altitude = strtol(argv[optind+1], nullptr, 10);
- ms5611::calibrate(altitude);
+ ms5611::calibrate(altitude, external_bus);
}
errx(1, "unrecognised command, try 'start', 'test', 'reset' or 'info'");
diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk
index 460bec7b9..ecd3e804a 100644
--- a/src/drivers/px4flow/module.mk
+++ b/src/drivers/px4flow/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-attributes
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index 09ec4bf96..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
@@ -106,7 +109,7 @@ struct i2c_frame {
};
struct i2c_frame f;
-typedef struct i2c_integral_frame {
+struct i2c_integral_frame {
uint16_t frame_count_since_last_readout;
int16_t pixel_flow_x_integral;
int16_t pixel_flow_y_integral;
@@ -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/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp
index 44ed03254..83086fd7c 100644
--- a/src/drivers/roboclaw/roboclaw_main.cpp
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -109,7 +109,7 @@ int roboclaw_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
2048,
roboclaw_thread_main,
- (const char **)argv);
+ (char * const *)argv);
exit(0);
} else if (!strcmp(argv[1], "test")) {
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 4301750f0..8e62e0d4b 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -90,7 +90,9 @@ static const int ERROR = -1;
#define SF0X_TAKE_RANGE_REG 'd'
#define SF02F_MIN_DISTANCE 0.0f
#define SF02F_MAX_DISTANCE 40.0f
-#define SF0X_DEFAULT_PORT "/dev/ttyS2"
+
+// designated SERIAL4/5 on Pixhawk
+#define SF0X_DEFAULT_PORT "/dev/ttyS6"
class SF0X : public device::CDev
{
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 281f918d7..603c2eb9d 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -253,9 +253,11 @@ static uint16_t latency_baseline;
static uint16_t latency_actual;
/* latency histogram */
-#define LATENCY_BUCKET_COUNT 8
-static const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
-static uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+#define LATENCY_BUCKET_COUNT 8
+__EXPORT const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
+__EXPORT const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
+__EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+
/* timer-specific functions */
static void hrt_tim_init(void);
diff --git a/src/drivers/trone/trone.cpp b/src/drivers/trone/trone.cpp
index 83b5c987e..cf3546669 100644
--- a/src/drivers/trone/trone.cpp
+++ b/src/drivers/trone/trone.cpp
@@ -206,7 +206,7 @@ static const uint8_t crc_table[] = {
0xfa, 0xfd, 0xf4, 0xf3
};
-uint8_t crc8(uint8_t *p, uint8_t len){
+static uint8_t crc8(uint8_t *p, uint8_t len) {
uint16_t i;
uint16_t crc = 0x0;
diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c
index 6a5cbcd30..fcbb54c8e 100644
--- a/src/examples/fixedwing_control/main.c
+++ b/src/examples/fixedwing_control/main.c
@@ -423,7 +423,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 20,
2048,
fixedwing_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
thread_running = true;
exit(0);
}
diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk
index a2a9eb113..f6c882ead 100644
--- a/src/examples/fixedwing_control/module.mk
+++ b/src/examples/fixedwing_control/module.mk
@@ -41,3 +41,5 @@ SRCS = main.c \
params.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wframe-larger-than=1200
diff --git a/src/examples/flow_position_estimator/flow_position_estimator_main.c b/src/examples/flow_position_estimator/flow_position_estimator_main.c
index 0b8c01f79..a89ccf933 100644
--- a/src/examples/flow_position_estimator/flow_position_estimator_main.c
+++ b/src/examples/flow_position_estimator/flow_position_estimator_main.c
@@ -114,7 +114,7 @@ int flow_position_estimator_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
4000,
flow_position_estimator_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/examples/flow_position_estimator/module.mk b/src/examples/flow_position_estimator/module.mk
index 88c9ceb93..5c6e29f8f 100644
--- a/src/examples/flow_position_estimator/module.mk
+++ b/src/examples/flow_position_estimator/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = flow_position_estimator
SRCS = flow_position_estimator_main.c \
flow_position_estimator_params.c
+
+EXTRACFLAGS = -Wno-float-equal
diff --git a/src/examples/hwtest/hwtest.c b/src/examples/hwtest/hwtest.c
index d3b10f46e..95ff346bb 100644
--- a/src/examples/hwtest/hwtest.c
+++ b/src/examples/hwtest/hwtest.c
@@ -39,13 +39,15 @@
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
-#include <nuttx/config.h>
#include <stdio.h>
-#include <systemlib/err.h>
+#include <string.h>
+
#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/actuator_controls.h>
+#include <nuttx/config.h>
+#include <systemlib/err.h>
#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/uORB.h>
__EXPORT int ex_hwtest_main(int argc, char *argv[]);
@@ -53,7 +55,7 @@ int ex_hwtest_main(int argc, char *argv[])
{
warnx("DO NOT FORGET TO STOP THE COMMANDER APP!");
warnx("(run <commander stop> to do so)");
- warnx("usage: http://px4.io/dev/examples/write_output");
+ warnx("usage: http://px4.io/dev/examples/write_output");
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c
index c66bebeec..a95f45d1a 100644
--- a/src/examples/matlab_csv_serial/matlab_csv_serial.c
+++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c
@@ -107,7 +107,7 @@ int matlab_csv_serial_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
2000,
matlab_csv_serial_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index 3eaf14148..45d541137 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -38,10 +38,13 @@
* @author Example User <mail@example.com>
*/
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
#include <nuttx/config.h>
#include <nuttx/sched.h>
-#include <unistd.h>
-#include <stdio.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
@@ -100,7 +103,7 @@ int px4_daemon_app_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
px4_daemon_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/lib/conversion/rotation.cpp b/src/lib/conversion/rotation.cpp
index e17715733..1fe36d395 100644
--- a/src/lib/conversion/rotation.cpp
+++ b/src/lib/conversion/rotation.cpp
@@ -181,6 +181,11 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z)
x = tmp;
return;
}
+ case ROTATION_ROLL_270_YAW_270: {
+ tmp = z; z = -y; y = tmp;
+ tmp = x; x = y; y = -tmp;
+ return;
+ }
case ROTATION_PITCH_90: {
tmp = z; z = -x; x = tmp;
return;
diff --git a/src/lib/rc/st24.c b/src/lib/rc/st24.c
index e8a791b8f..5c53a1602 100644
--- a/src/lib/rc/st24.c
+++ b/src/lib/rc/st24.c
@@ -72,7 +72,7 @@ const char *decode_states[] = {"UNSYNCED",
#define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
static enum ST24_DECODE_STATE _decode_state = ST24_DECODE_STATE_UNSYNCED;
-static unsigned _rxlen;
+static uint8_t _rxlen;
static ReceiverFcPacket _rxpacket;
diff --git a/src/lib/uavcan b/src/lib/uavcan
new file mode 160000
+Subproject 1efd24427539fa332a15151143466ec760fa5ff
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 6068ab082..702894d60 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -63,6 +63,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <drivers/drv_hrt.h>
#include <lib/mathlib/mathlib.h>
@@ -134,7 +135,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
7200,
attitude_estimator_ekf_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
@@ -207,7 +208,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
}; /**< init: identity matrix */
float debugOutput[4] = { 0.0f };
-
int overloadcounter = 19;
/* Initialize filter */
@@ -220,6 +220,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
memset(&raw, 0, sizeof(raw));
struct vehicle_gps_position_s gps;
memset(&gps, 0, sizeof(gps));
+ gps.eph = 100000;
+ gps.epv = 100000;
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
struct vehicle_attitude_s att;
@@ -258,9 +260,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
- /* subscribe to control mode*/
+ /* subscribe to control mode */
int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
+ /* subscribe to vision estimate */
+ int vision_sub = orb_subscribe(ORB_ID(vision_position_estimate));
+
/* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
@@ -268,14 +273,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
thread_running = true;
- /* advertise debug value */
- // struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
- // orb_advert_t pub_dbg = -1;
-
/* keep track of sensor updates */
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
- struct attitude_estimator_ekf_params ekf_params = { 0 };
+ struct attitude_estimator_ekf_params ekf_params;
+ memset(&ekf_params, 0, sizeof(ekf_params));
struct attitude_estimator_ekf_param_handles ekf_param_handles = { 0 };
@@ -293,6 +295,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
math::Matrix<3, 3> R_decl;
R_decl.identity();
+ struct vision_position_estimate vision {};
+
/* register the perf counter */
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");
@@ -313,8 +317,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_copy(ORB_ID(vehicle_control_mode), sub_control_mode, &control_mode);
if (!control_mode.flag_system_hil_enabled) {
- fprintf(stderr,
- "[att ekf] WARNING: Not getting sensors - sensor app running?\n");
+ warnx("WARNING: Not getting sensors - sensor app running?");
}
} else {
@@ -449,9 +452,30 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
- z_k[6] = raw.magnetometer_ga[0];
- z_k[7] = raw.magnetometer_ga[1];
- z_k[8] = raw.magnetometer_ga[2];
+ bool vision_updated = false;
+ orb_check(vision_sub, &vision_updated);
+
+ if (vision_updated) {
+ orb_copy(ORB_ID(vision_position_estimate), vision_sub, &vision);
+ }
+
+ if (vision.timestamp_boot > 0 && (hrt_elapsed_time(&vision.timestamp_boot) < 500000)) {
+
+ math::Quaternion q(vision.q);
+ math::Matrix<3, 3> Rvis = q.to_dcm();
+
+ math::Vector<3> v(1.0f, 0.0f, 0.4f);
+
+ math::Vector<3> vn = Rvis * v;
+
+ z_k[6] = vn(0);
+ z_k[7] = vn(1);
+ z_k[8] = vn(2);
+ } else {
+ z_k[6] = raw.magnetometer_ga[0];
+ z_k[7] = raw.magnetometer_ga[1];
+ z_k[8] = raw.magnetometer_ga[2];
+ }
uint64_t now = hrt_absolute_time();
unsigned int time_elapsed = now - last_run;
diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk
index 749b0a91c..1158536e1 100644
--- a/src/modules/attitude_estimator_ekf/module.mk
+++ b/src/modules/attitude_estimator_ekf/module.mk
@@ -42,3 +42,7 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/AttitudeEKF.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wno-float-equal -Wframe-larger-than=3600
+
+EXTRACXXFLAGS = -Wframe-larger-than=2400
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index e49027e47..9414225ca 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -153,7 +153,7 @@ int attitude_estimator_so3_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
14000,
attitude_estimator_so3_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk
index f52715abb..7b2e206cc 100644
--- a/src/modules/attitude_estimator_so3/module.mk
+++ b/src/modules/attitude_estimator_so3/module.mk
@@ -8,3 +8,5 @@ SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Wno-float-equal
diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp
index e0bcbc6e9..4580b338d 100644
--- a/src/modules/bottle_drop/bottle_drop.cpp
+++ b/src/modules/bottle_drop/bottle_drop.cpp
@@ -523,6 +523,9 @@ BottleDrop::task_main()
}
switch (_drop_state) {
+ case DROP_STATE_INIT:
+ // do nothing
+ break;
case DROP_STATE_TARGET_VALID:
{
@@ -689,6 +692,10 @@ BottleDrop::task_main()
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
}
break;
+
+ case DROP_STATE_BAY_CLOSED:
+ // do nothing
+ break;
}
counter++;
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 744323c01..086f291f6 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -81,6 +81,7 @@
#include <uORB/topics/system_power.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
+#include <uORB/topics/geofence_result.h>
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/vtol_vehicle_status.h>
@@ -267,7 +268,7 @@ int commander_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 40,
3200,
commander_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
while (!thread_running) {
usleep(200);
@@ -926,6 +927,11 @@ int commander_thread_main(int argc, char *argv[])
struct mission_result_s mission_result;
memset(&mission_result, 0, sizeof(mission_result));
+ /* Subscribe to geofence result topic */
+ int geofence_result_sub = orb_subscribe(ORB_ID(geofence_result));
+ struct geofence_result_s geofence_result;
+ memset(&geofence_result, 0, sizeof(geofence_result));
+
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
struct manual_control_setpoint_s sp_man;
@@ -1092,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));
@@ -1113,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);
@@ -1121,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);
}
@@ -1253,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;
@@ -1545,27 +1559,34 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
+ }
- /* Check for geofence violation */
- if (armed.armed && (mission_result.geofence_violated || mission_result.flight_termination)) {
- //XXX: make this configurable to select different actions (e.g. navigation modes)
- /* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
- armed.force_failsafe = true;
- status_changed = true;
- static bool flight_termination_printed = false;
-
- if (!flight_termination_printed) {
- warnx("Flight termination because of navigator request or geofence");
- mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
- flight_termination_printed = true;
- }
+ /* start geofence result check */
+ orb_check(geofence_result_sub, &updated);
- if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
- }
- } // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
+ if (updated) {
+ orb_copy(ORB_ID(geofence_result), geofence_result_sub, &geofence_result);
}
+ /* Check for geofence violation */
+ if (armed.armed && (geofence_result.geofence_violated || mission_result.flight_termination)) {
+ //XXX: make this configurable to select different actions (e.g. navigation modes)
+ /* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
+ armed.force_failsafe = true;
+ status_changed = true;
+ static bool flight_termination_printed = false;
+
+ if (!flight_termination_printed) {
+ warnx("Flight termination because of navigator request or geofence");
+ mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
+ flight_termination_printed = true;
+ }
+
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
+ }
+ } // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
+
/* RC input check */
if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
@@ -2217,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;
@@ -2232,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/commander/module.mk b/src/modules/commander/module.mk
index 27ca5c182..0e2a5356b 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -51,3 +51,6 @@ SRCS = commander.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wframe-larger-than=2000
+
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 36d854ddd..843dde978 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -42,4 +42,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \
estimator_23states.cpp \
estimator_utilities.cpp
-EXTRACXXFLAGS = -Weffc++
+EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=6100
+
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index f4ea05088..71b387b1e 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -115,7 +115,7 @@ int fixedwing_backside_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
5120,
control_demo_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
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/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 948b29bcb..dbf15d98a 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -200,9 +200,11 @@ private:
ECL_L1_Pos_Controller _l1_control;
TECS _tecs;
fwPosctrl::mTecs _mTecs;
- bool _was_pos_control_mode;
- bool _was_velocity_control_mode;
- bool _was_alt_control_mode;
+ enum FW_POSCTRL_MODE {
+ FW_POSCTRL_MODE_AUTO,
+ FW_POSCTRL_MODE_POSITION,
+ FW_POSCTRL_MODE_OTHER
+ } _control_mode_current; ///< used to check the mode in the last control loop iteration. Use to check if the last iteration was in the same mode.
struct {
float l1_period;
@@ -471,7 +473,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_global_pos_valid(false),
_l1_control(),
_mTecs(),
- _was_pos_control_mode(false)
+ _control_mode_current(FW_POSCTRL_MODE_OTHER)
{
_nav_capabilities.turn_distance = 0.0f;
@@ -908,22 +910,19 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* no throttle limit as default */
float throttle_max = 1.0f;
- /* AUTONOMOUS FLIGHT */
+ if (_control_mode.flag_control_auto_enabled &&
+ pos_sp_triplet.current.valid) {
+ /* AUTONOMOUS FLIGHT */
- // XXX this should only execute if auto AND safety off (actuators active),
- // else integrators should be constantly reset.
- if (pos_sp_triplet.current.valid) {
-
- if (!_was_pos_control_mode) {
+ /* Reset integrators if switching to this mode from a other mode in which posctl was not active */
+ if (_control_mode_current == FW_POSCTRL_MODE_OTHER) {
/* reset integrators */
if (_mTecs.getEnabled()) {
_mTecs.resetIntegrators();
_mTecs.resetDerivatives(_airspeed.true_airspeed_m_s);
}
}
-
- _was_pos_control_mode = true;
- _was_velocity_control_mode = false;
+ _control_mode_current = FW_POSCTRL_MODE_AUTO;
/* reset hold altitude */
_hold_alt = _global_pos.alt;
@@ -1208,15 +1207,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
calculate_target_airspeed(_parameters.airspeed_trim),
eas2tas,
- math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
- _parameters.throttle_min,
- takeoff_throttle,
- _parameters.throttle_cruise,
- false,
- math::radians(_parameters.pitch_limit_min),
- _global_pos.alt,
- ground_speed);
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ takeoff_throttle,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed);
}
} else {
/* Tell the attitude controller to stop integrating while we are waiting
@@ -1248,53 +1247,63 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.roll_reset_integral = true;
}
- } else if (_control_mode.flag_control_velocity_enabled) {
+ } else if (_control_mode.flag_control_velocity_enabled &&
+ _control_mode.flag_control_altitude_enabled) {
+ /* POSITION CONTROL: pitch stick moves altitude setpoint, throttle stick sets airspeed */
+
const float deadBand = (60.0f/1000.0f);
const float factor = 1.0f - deadBand;
- if (!_was_velocity_control_mode) {
+ if (_control_mode_current != FW_POSCTRL_MODE_POSITION) {
+ /* Need to init because last loop iteration was in a different mode */
_hold_alt = _global_pos.alt;
- _was_alt_control_mode = false;
}
- _was_velocity_control_mode = true;
- _was_pos_control_mode = false;
- // Get demanded airspeed
+ /* Reset integrators if switching to this mode from a other mode in which posctl was not active */
+ if (_control_mode_current == FW_POSCTRL_MODE_OTHER) {
+ /* reset integrators */
+ if (_mTecs.getEnabled()) {
+ _mTecs.resetIntegrators();
+ _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s);
+ }
+ }
+ _control_mode_current = FW_POSCTRL_MODE_POSITION;
+
+ /* Get demanded airspeed */
float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
_manual.z;
- // Get demanded vertical velocity from pitch control
- float pitch = 0.0f;
+ /* Get demanded vertical velocity from pitch control */
+ static bool was_in_deadband = false;
if (_manual.x > deadBand) {
- pitch = (_manual.x - deadBand) / factor;
- } else if (_manual.x < - deadBand) {
- pitch = (_manual.x + deadBand) / factor;
- }
- if (pitch > 0.0f) {
+ float pitch = (_manual.x - deadBand) / factor;
_hold_alt -= (_parameters.max_climb_rate * dt) * pitch;
- _was_alt_control_mode = false;
- } else if (pitch < 0.0f) {
+ was_in_deadband = false;
+ } else if (_manual.x < - deadBand) {
+ float pitch = (_manual.x + deadBand) / factor;
_hold_alt -= (_parameters.max_sink_rate * dt) * pitch;
- _was_alt_control_mode = false;
- } else if (!_was_alt_control_mode) {
+ was_in_deadband = false;
+ } else if (!was_in_deadband) {
+ /* store altitude at which manual.x was inside deadBand
+ * The aircraft should immediately try to fly at this altitude
+ * as this is what the pilot expects when he moves the stick to the center */
_hold_alt = _global_pos.alt;
- _was_alt_control_mode = true;
+ was_in_deadband = true;
}
tecs_update_pitch_throttle(_hold_alt,
- altctrl_airspeed,
- eas2tas,
- math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
- _parameters.throttle_min,
- _parameters.throttle_max,
- _parameters.throttle_cruise,
- false,
- math::radians(_parameters.pitch_limit_min),
- _global_pos.alt,
- ground_speed,
- TECS_MODE_NORMAL);
+ altctrl_airspeed,
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed,
+ TECS_MODE_NORMAL);
} else {
- _was_velocity_control_mode = false;
- _was_pos_control_mode = false;
+ _control_mode_current = FW_POSCTRL_MODE_OTHER;
/** MANUAL FLIGHT **/
@@ -1311,10 +1320,12 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
+ /* Copy thrust output for publication */
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
/* Set thrust to 0 to minimize damage */
_att_sp.thrust = 0.0f;
- } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ } else if (_control_mode_current == FW_POSCTRL_MODE_AUTO && // launchdetector only available in auto
+ pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
/* making sure again that the correct thrust is used,
* without depending on library calls for safety reasons */
@@ -1327,8 +1338,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* During a takeoff waypoint while waiting for launch the pitch sp is set
* already (not by tecs) */
- if (!(pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
- launch_detection_state == LAUNCHDETECTION_RES_NONE)) {
+ if (!(_control_mode_current == FW_POSCTRL_MODE_AUTO &&
+ pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ launch_detection_state == LAUNCHDETECTION_RES_NONE)) {
_att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
}
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
index 440bab2c5..98e5c0a1e 100644
--- a/src/modules/fw_pos_control_l1/module.mk
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -47,3 +47,5 @@ SRCS = fw_pos_control_l1_main.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-float-equal
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index f17497aa8..4ba595a87 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -801,7 +801,7 @@ MavlinkFTP::_return_request(Request *req)
/// @brief Copy file (with limited space)
int
-MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
+MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length)
{
char buff[512];
int src_fd = -1, dst_fd = -1;
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index bef6775a9..9693a92a9 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -142,7 +142,7 @@ private:
static void _worker_trampoline(void *arg);
void _process_request(Request *req);
void _reply(Request *req);
- int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
+ int _copy_file(const char *src_path, const char *dst_path, size_t length);
ErrorCode _workList(PayloadHeader *payload);
ErrorCode _workOpen(PayloadHeader *payload, int oflag);
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 29b7ec7b7..f9a3681b3 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -948,7 +948,6 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
/* delete stream */
LL_DELETE(_streams, stream);
delete stream;
- warnx("deleted stream %s", stream->get_name());
}
return OK;
@@ -1412,9 +1411,13 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("SYS_STATUS", 1.0f);
configure_stream("ATTITUDE", 50.0f);
configure_stream("GLOBAL_POSITION_INT", 50.0f);
+ configure_stream("LOCAL_POSITION_NED", 30.0f);
configure_stream("CAMERA_CAPTURE", 2.0f);
configure_stream("ATTITUDE_TARGET", 10.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
+ configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
+ configure_stream("DISTANCE_SENSOR", 10.0f);
+ configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("VFR_HUD", 10.0f);
break;
@@ -1638,7 +1641,7 @@ Mavlink::start(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2800,
(main_t)&Mavlink::start_helper,
- (const char **)argv);
+ (char * const *)argv);
// Ensure that this shell command
// does not return before the instance
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 378e3427d..0f25c969d 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -1486,6 +1486,7 @@ protected:
if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) {
mavlink_position_target_global_int_t msg{};
+ msg.time_boot_ms = hrt_absolute_time()/1000;
msg.coordinate_frame = MAV_FRAME_GLOBAL;
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
msg.lon_int = pos_sp_triplet.current.lon * 1e7;
@@ -1764,6 +1765,9 @@ protected:
case RC_INPUT_SOURCE_PX4IO_ST24:
msg.rssi |= (3 << 4);
break;
+ case RC_INPUT_SOURCE_UNKNOWN:
+ // do nothing
+ break;
}
if (rc.rc_lost) {
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
index a3c127cdc..859d380fe 100644
--- a/src/modules/mavlink/mavlink_mission.cpp
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -292,9 +292,6 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
void
MavlinkMissionManager::send(const hrt_abstime now)
{
- /* update interval for slow rate limiter */
- _slow_rate_limiter.set_interval(_interval * 10 / _mavlink->get_rate_mult());
-
bool updated = false;
orb_check(_mission_result_sub, &updated);
@@ -312,6 +309,12 @@ MavlinkMissionManager::send(const hrt_abstime now)
send_mission_current(_current_seq);
+ if (mission_result.item_do_jump_changed) {
+ /* send a mission item again if the remaining DO_JUMPs has changed */
+ send_mission_item(_transfer_partner_sysid, _transfer_partner_compid,
+ (uint16_t)mission_result.item_changed_index);
+ }
+
} else {
if (_slow_rate_limiter.check(now)) {
send_mission_current(_current_seq);
@@ -811,7 +814,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
case NAV_CMD_DO_JUMP:
mavlink_mission_item->param1 = mission_item->do_jump_mission_index;
- mavlink_mission_item->param2 = mission_item->do_jump_repeat_count;
+ mavlink_mission_item->param2 = mission_item->do_jump_repeat_count - mission_item->do_jump_current_count;
break;
default:
diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp
index cd5f53d88..e9858b73c 100644
--- a/src/modules/mavlink/mavlink_parameters.cpp
+++ b/src/modules/mavlink/mavlink_parameters.cpp
@@ -44,7 +44,9 @@
#include "mavlink_main.h"
MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink),
- _send_all_index(-1)
+ _send_all_index(-1),
+ _rc_param_map_pub(-1),
+ _rc_param_map()
{
}
@@ -135,6 +137,43 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
break;
}
+ case MAVLINK_MSG_ID_PARAM_MAP_RC: {
+ /* map a rc channel to a parameter */
+ mavlink_param_map_rc_t map_rc;
+ mavlink_msg_param_map_rc_decode(msg, &map_rc);
+
+ if (map_rc.target_system == mavlink_system.sysid &&
+ (map_rc.target_component == mavlink_system.compid ||
+ map_rc.target_component == MAV_COMP_ID_ALL)) {
+
+ /* Copy values from msg to uorb using the parameter_rc_channel_index as index */
+ size_t i = map_rc.parameter_rc_channel_index;
+ _rc_param_map.param_index[i] = map_rc.param_index;
+ strncpy(&(_rc_param_map.param_id[i][0]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
+ /* enforce null termination */
+ _rc_param_map.param_id[i][MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = '\0';
+ _rc_param_map.scale[i] = map_rc.scale;
+ _rc_param_map.value0[i] = map_rc.param_value0;
+ _rc_param_map.value_min[i] = map_rc.param_value_min;
+ _rc_param_map.value_max[i] = map_rc.param_value_max;
+ if (map_rc.param_index == -2) { // -2 means unset map
+ _rc_param_map.valid[i] = false;
+ } else {
+ _rc_param_map.valid[i] = true;
+ }
+ _rc_param_map.timestamp = hrt_absolute_time();
+
+ if (_rc_param_map_pub < 0) {
+ _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map);
+
+ } else {
+ orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map);
+ }
+
+ }
+ break;
+ }
+
default:
break;
}
diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h
index 5576e6b84..b6736f212 100644
--- a/src/modules/mavlink/mavlink_parameters.h
+++ b/src/modules/mavlink/mavlink_parameters.h
@@ -44,6 +44,8 @@
#include "mavlink_bridge_header.h"
#include "mavlink_stream.h"
+#include <uORB/uORB.h>
+#include <uORB/topics/rc_parameter_map.h>
class MavlinkParametersManager : public MavlinkStream
{
@@ -112,4 +114,7 @@ protected:
void send(const hrt_abstime t);
void send_param(param_t param);
+
+ orb_advert_t _rc_param_map_pub;
+ struct rc_parameter_map_s _rc_param_map;
};
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/mavlink/module.mk b/src/modules/mavlink/module.mk
index 91fdd6154..f9d30dcbe 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -53,4 +53,6 @@ MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1024
-EXTRACXXFLAGS = -Weffc++
+EXTRACXXFLAGS = -Weffc++ -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/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 5918d6bc5..3b631e2ce 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -652,8 +652,6 @@ MulticopterPositionControl::control_offboard(float dt)
/* control position */
_pos_sp(0) = _pos_sp_triplet.current.x;
_pos_sp(1) = _pos_sp_triplet.current.y;
- _pos_sp(2) = _pos_sp_triplet.current.z;
-
} else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
/* control velocity */
/* reset position setpoint to current position if needed */
@@ -670,7 +668,10 @@ MulticopterPositionControl::control_offboard(float dt)
_att_sp.yaw_body = _att_sp.yaw_body + _pos_sp_triplet.current.yawspeed * dt;
}
- if (_control_mode.flag_control_altitude_enabled) {
+ if (_control_mode.flag_control_altitude_enabled && _pos_sp_triplet.current.position_valid) {
+ /* Control altitude */
+ _pos_sp(2) = _pos_sp_triplet.current.z;
+ } else if (_control_mode.flag_control_climb_rate_enabled && _pos_sp_triplet.current.velocity_valid) {
/* reset alt setpoint to current altitude if needed */
reset_alt_sp();
diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp
index e789fd10d..87a6e023a 100644
--- a/src/modules/navigator/datalinkloss.cpp
+++ b/src/modules/navigator/datalinkloss.cpp
@@ -155,7 +155,7 @@ DataLinkLoss::set_dll_item()
case DLL_STATE_TERMINATE: {
/* Request flight termination from the commander */
_navigator->get_mission_result()->flight_termination = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
warnx("not switched to manual: request flight termination");
pos_sp_triplet->previous.valid = false;
@@ -188,7 +188,7 @@ DataLinkLoss::advance_dll()
_navigator->get_vstatus()->data_link_lost_counter, _param_numberdatalinklosses.get());
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: too many DL losses, fly to airfield home");
_navigator->get_mission_result()->stay_in_failsafe = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
_dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
} else {
@@ -209,7 +209,7 @@ DataLinkLoss::advance_dll()
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to airfield home");
_dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
_navigator->get_mission_result()->stay_in_failsafe = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
break;
case DLL_STATE_FLYTOAIRFIELDHOMEWP:
@@ -217,7 +217,7 @@ DataLinkLoss::advance_dll()
warnx("time is up, state should have been changed manually by now");
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no manual control, terminating");
_navigator->get_mission_result()->stay_in_failsafe = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
break;
case DLL_STATE_TERMINATE:
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index 0f431ded2..4482fb36b 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -279,8 +279,14 @@ Geofence::loadFromFile(const char *filename)
while((textStart < sizeof(line)/sizeof(char)) && isspace(line[textStart])) textStart++;
/* if the line starts with #, skip */
- if (line[textStart] == commentChar)
+ if (line[textStart] == commentChar) {
continue;
+ }
+
+ /* if there is only a linefeed, skip it */
+ if (line[0] == '\n') {
+ continue;
+ }
if (gotVertical) {
/* Parse the line as a geofence point */
@@ -291,8 +297,10 @@ Geofence::loadFromFile(const char *filename)
/* Handle degree minute second format */
float lat_d, lat_m, lat_s, lon_d, lon_m, lon_s;
- if (sscanf(line, "DMS %f %f %f %f %f %f", &lat_d, &lat_m, &lat_s, &lon_d, &lon_m, &lon_s) != 6)
+ if (sscanf(line, "DMS %f %f %f %f %f %f", &lat_d, &lat_m, &lat_s, &lon_d, &lon_m, &lon_s) != 6) {
+ warnx("Scanf to parse DMS geofence vertex failed.");
return ERROR;
+ }
// warnx("Geofence DMS: %.5f %.5f %.5f ; %.5f %.5f %.5f", (double)lat_d, (double)lat_m, (double)lat_s, (double)lon_d, (double)lon_m, (double)lon_s);
@@ -301,9 +309,10 @@ Geofence::loadFromFile(const char *filename)
} else {
/* Handle decimal degree format */
-
- if (sscanf(line, "%f %f", &(vertex.lat), &(vertex.lon)) != 2)
+ if (sscanf(line, "%f %f", &(vertex.lat), &(vertex.lon)) != 2) {
+ warnx("Scanf to parse geofence vertex failed.");
return ERROR;
+ }
}
if (dm_write(DM_KEY_FENCE_POINTS, pointCounter, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) != sizeof(vertex))
diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp
index cd55f60b0..e370796c0 100644
--- a/src/modules/navigator/gpsfailure.cpp
+++ b/src/modules/navigator/gpsfailure.cpp
@@ -141,7 +141,7 @@ GpsFailure::set_gpsf_item()
case GPSF_STATE_TERMINATE: {
/* Request flight termination from the commander */
_navigator->get_mission_result()->flight_termination = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
warnx("gps fail: request flight termination");
}
default:
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index 0765e9b7c..9b0a092da 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -38,6 +38,7 @@
* @author Julian Oes <julian@oes.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Ban Siesta <bansiesta@gmail.com>
*/
#include <sys/types.h>
@@ -149,18 +150,12 @@ Mission::on_active()
/* lets check if we reached the current mission item */
if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
+ set_mission_item_reached();
if (_mission_item.autocontinue) {
/* switch to next waypoint if 'autocontinue' flag set */
advance_mission();
set_mission_items();
- } else {
- /* else just report that item reached */
- if (_mission_type == MISSION_TYPE_OFFBOARD) {
- if (!(_navigator->get_mission_result()->seq_reached == _current_offboard_mission_index && _navigator->get_mission_result()->reached)) {
- set_mission_item_reached();
- }
- }
}
} else if (_mission_type != MISSION_TYPE_NONE &&_param_altmode.get() == MISSION_ALTMODE_FOH) {
@@ -395,7 +390,6 @@ Mission::set_mission_items()
/* reuse setpoint for LOITER only if it's not IDLE */
_navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
- reset_mission_item_reached();
set_mission_finished();
_navigator->set_position_setpoint_triplet_updated();
@@ -636,6 +630,8 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s
"ERROR DO JUMP waypoint could not be written");
return false;
}
+ report_do_jump_mission_changed(*mission_index_ptr,
+ mission_item_tmp.do_jump_repeat_count);
}
/* set new mission item index and repeat
* we don't have to validate here, if it's invalid, we should realize this later .*/
@@ -707,22 +703,31 @@ Mission::save_offboard_mission_state()
}
void
+Mission::report_do_jump_mission_changed(int index, int do_jumps_remaining)
+{
+ /* inform about the change */
+ _navigator->get_mission_result()->item_do_jump_changed = true;
+ _navigator->get_mission_result()->item_changed_index = index;
+ _navigator->get_mission_result()->item_do_jump_remaining = do_jumps_remaining;
+ _navigator->set_mission_result_updated();
+}
+
+void
Mission::set_mission_item_reached()
{
_navigator->get_mission_result()->reached = true;
_navigator->get_mission_result()->seq_reached = _current_offboard_mission_index;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
}
void
Mission::set_current_offboard_mission_item()
{
- warnx("current offboard mission index: %d", _current_offboard_mission_index);
_navigator->get_mission_result()->reached = false;
_navigator->get_mission_result()->finished = false;
_navigator->get_mission_result()->seq_current = _current_offboard_mission_index;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
save_offboard_mission_state();
}
@@ -731,5 +736,5 @@ void
Mission::set_mission_finished()
{
_navigator->get_mission_result()->finished = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
}
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
index ea7cc0927..a8a644b0f 100644
--- a/src/modules/navigator/mission.h
+++ b/src/modules/navigator/mission.h
@@ -38,6 +38,7 @@
* @author Julian Oes <julian@oes.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Ban Siesta <bansiesta@gmail.com>
*/
#ifndef NAVIGATOR_MISSION_H
@@ -131,6 +132,11 @@ private:
void save_offboard_mission_state();
/**
+ * Inform about a changed mission item after a DO_JUMP
+ */
+ void report_do_jump_mission_changed(int index, int do_jumps_remaining);
+
+ /**
* Set a mission item as reached
*/
void set_mission_item_reached();
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index c44d4c35e..0d7d6b9ef 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -62,3 +62,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-sign-compare
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 9cd609955..d9d911d9c 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -54,6 +54,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission_result.h>
+#include <uORB/topics/geofence_result.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include "navigator_mode.h"
@@ -107,9 +108,9 @@ public:
void load_fence_from_file(const char *filename);
/**
- * Publish the mission result so commander and mavlink know what is going on
+ * Publish the geofence result
*/
- void publish_mission_result();
+ void publish_geofence_result();
/**
* Publish the attitude sp, only to be used in very special modes when position control is deactivated
@@ -122,6 +123,7 @@ public:
*/
void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; }
void set_position_setpoint_triplet_updated() { _pos_sp_triplet_updated = true; }
+ void set_mission_result_updated() { _mission_result_updated = true; }
/**
* Getters
@@ -134,6 +136,7 @@ public:
struct home_position_s* get_home_position() { return &_home_pos; }
struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
struct mission_result_s* get_mission_result() { return &_mission_result; }
+ struct geofence_result_s* get_geofence_result() { return &_geofence_result; }
struct vehicle_attitude_setpoint_s* get_att_sp() { return &_att_sp; }
int get_onboard_mission_sub() { return _onboard_mission_sub; }
@@ -164,6 +167,7 @@ private:
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
orb_advert_t _mission_result_pub;
+ orb_advert_t _geofence_result_pub;
orb_advert_t _att_sp_pub; /**< publish att sp
used only in very special failsafe modes
when pos control is deactivated */
@@ -179,7 +183,8 @@ private:
position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
mission_result_s _mission_result;
- vehicle_attitude_setpoint_s _att_sp;
+ geofence_result_s _geofence_result;
+ vehicle_attitude_setpoint_s _att_sp;
bool _mission_item_valid; /**< flags if the current mission item is valid */
@@ -206,6 +211,7 @@ private:
bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */
bool _pos_sp_triplet_updated; /**< flags if position SP triplet needs to be published */
bool _pos_sp_triplet_published_invalid_once; /**< flags if position SP triplet has been published once to UORB */
+ bool _mission_result_updated; /**< flags if mission result has seen an update */
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
@@ -271,6 +277,12 @@ private:
*/
void publish_position_setpoint_triplet();
+
+ /**
+ * Publish the mission result so commander and mavlink know what is going on
+ */
+ void publish_mission_result();
+
/* this class has ptr data members, so it should not be copied,
* consequently the copy constructors are private.
*/
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index df620e5e7..3f7670ec4 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -110,6 +110,7 @@ Navigator::Navigator() :
_param_update_sub(-1),
_pos_sp_triplet_pub(-1),
_mission_result_pub(-1),
+ _geofence_result_pub(-1),
_att_sp_pub(-1),
_vstatus{},
_control_mode{},
@@ -138,6 +139,7 @@ Navigator::Navigator() :
_can_loiter_at_sp(false),
_pos_sp_triplet_updated(false),
_pos_sp_triplet_published_invalid_once(false),
+ _mission_result_updated(false),
_param_loiter_radius(this, "LOITER_RAD"),
_param_acceptance_radius(this, "ACC_RAD"),
_param_datalinkloss_obc(this, "DLL_OBC"),
@@ -398,8 +400,8 @@ Navigator::task_main()
have_geofence_position_data = false;
if (!inside) {
/* inform other apps via the mission result */
- _mission_result.geofence_violated = true;
- publish_mission_result();
+ _geofence_result.geofence_violated = true;
+ publish_geofence_result();
/* Issue a warning about the geofence violation once */
if (!_geofence_violation_warning_sent) {
@@ -408,8 +410,8 @@ Navigator::task_main()
}
} else {
/* inform other apps via the mission result */
- _mission_result.geofence_violated = false;
- publish_mission_result();
+ _geofence_result.geofence_violated = false;
+ publish_geofence_result();
/* Reset the _geofence_violation_warning_sent field */
_geofence_violation_warning_sent = false;
}
@@ -490,6 +492,11 @@ Navigator::task_main()
_pos_sp_triplet_updated = false;
}
+ if (_mission_result_updated) {
+ publish_mission_result();
+ _mission_result_updated = false;
+ }
+
perf_end(_loop_perf);
}
warnx("exiting.");
@@ -639,6 +646,28 @@ Navigator::publish_mission_result()
/* advertise and publish */
_mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
}
+
+ /* reset some of the flags */
+ _mission_result.seq_reached = false;
+ _mission_result.seq_current = 0;
+ _mission_result.item_do_jump_changed = false;
+ _mission_result.item_changed_index = 0;
+ _mission_result.item_do_jump_remaining = 0;
+}
+
+void
+Navigator::publish_geofence_result()
+{
+
+ /* lazily publish the geofence result only once available */
+ if (_geofence_result_pub > 0) {
+ /* publish mission result */
+ orb_publish(ORB_ID(geofence_result), _geofence_result_pub, &_geofence_result);
+
+ } else {
+ /* advertise and publish */
+ _geofence_result_pub = orb_advertise(ORB_ID(geofence_result), &_geofence_result);
+ }
}
void
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
index 3807c5ea8..2f322031c 100644
--- a/src/modules/navigator/navigator_mode.cpp
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -65,7 +65,7 @@ NavigatorMode::run(bool active) {
_first_run = false;
/* Reset stay in failsafe flag */
_navigator->get_mission_result()->stay_in_failsafe = false;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
on_activation();
} else {
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/rcloss.cpp b/src/modules/navigator/rcloss.cpp
index 42392e739..a7cde6325 100644
--- a/src/modules/navigator/rcloss.cpp
+++ b/src/modules/navigator/rcloss.cpp
@@ -128,7 +128,7 @@ RCLoss::set_rcl_item()
case RCL_STATE_TERMINATE: {
/* Request flight termination from the commander */
_navigator->get_mission_result()->flight_termination = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
warnx("rc not recovered: request flight termination");
pos_sp_triplet->previous.valid = false;
pos_sp_triplet->current.valid = false;
@@ -162,7 +162,7 @@ RCLoss::advance_rcl()
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: rc loss, terminating");
_rcl_state = RCL_STATE_TERMINATE;
_navigator->get_mission_result()->stay_in_failsafe = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
}
break;
@@ -171,7 +171,7 @@ RCLoss::advance_rcl()
warnx("time is up, no RC regain, terminating");
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RC not regained, terminating");
_navigator->get_mission_result()->stay_in_failsafe = true;
- _navigator->publish_mission_result();
+ _navigator->set_mission_result_updated();
reset_mission_item_reached();
break;
case RCL_STATE_TERMINATE:
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/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
index 0658d3f09..45c876299 100644
--- a/src/modules/position_estimator_inav/module.mk
+++ b/src/modules/position_estimator_inav/module.mk
@@ -41,3 +41,6 @@ SRCS = position_estimator_inav_main.c \
inertial_filter.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wframe-larger-than=3500
+
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 296919c04..1962151fa 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -151,7 +151,7 @@ int position_estimator_inav_main(int argc, char *argv[])
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 5000,
position_estimator_inav_thread_main,
- (argv) ? (const char **) &argv[2] : (const char **) NULL);
+ (argv) ? (char * const *) &argv[2] : (char * const *) NULL);
exit(0);
}
@@ -233,8 +233,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float eph_flow = 1.0f;
- float eph_vision = 0.5f;
- float epv_vision = 0.5f;
+ float eph_vision = 0.2f;
+ float epv_vision = 0.2f;
float x_est_prev[2], y_est_prev[2], z_est_prev[2];
memset(x_est_prev, 0, sizeof(x_est_prev));
@@ -640,6 +640,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(vision_position_estimate), vision_position_estimate_sub, &vision);
+ static float last_vision_x = 0.0f;
+ static float last_vision_y = 0.0f;
+ static float last_vision_z = 0.0f;
+
/* reset position estimate on first vision update */
if (!vision_valid) {
x_est[0] = vision.x;
@@ -654,6 +658,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
vision_valid = true;
+
+ last_vision_x = vision.x;
+ last_vision_y = vision.y;
+ last_vision_z = vision.z;
+
warnx("VISION estimate valid");
mavlink_log_info(mavlink_fd, "[inav] VISION estimate valid");
}
@@ -663,10 +672,30 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_vision[1][0] = vision.y - y_est[0];
corr_vision[2][0] = vision.z - z_est[0];
- /* calculate correction for velocity */
- corr_vision[0][1] = vision.vx - x_est[1];
- corr_vision[1][1] = vision.vy - y_est[1];
- corr_vision[2][1] = vision.vz - z_est[1];
+ static hrt_abstime last_vision_time = 0;
+
+ float vision_dt = (vision.timestamp_boot - last_vision_time) / 1e6f;
+ last_vision_time = vision.timestamp_boot;
+
+ if (vision_dt > 0.000001f && vision_dt < 0.2f) {
+ vision.vx = (vision.x - last_vision_x) / vision_dt;
+ vision.vy = (vision.y - last_vision_y) / vision_dt;
+ vision.vz = (vision.z - last_vision_z) / vision_dt;
+
+ last_vision_x = vision.x;
+ last_vision_y = vision.y;
+ last_vision_z = vision.z;
+
+ /* calculate correction for velocity */
+ corr_vision[0][1] = vision.vx - x_est[1];
+ corr_vision[1][1] = vision.vy - y_est[1];
+ corr_vision[2][1] = vision.vz - z_est[1];
+ } else {
+ /* assume zero motion */
+ corr_vision[0][1] = 0.0f - x_est[1];
+ corr_vision[1][1] = 0.0f - y_est[1];
+ corr_vision[2][1] = 0.0f - z_est[1];
+ }
}
}
@@ -1052,10 +1081,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
landed = false;
landed_time = 0;
}
- /* reset xy velocity estimates when landed */
- x_est[1] = 0.0f;
- y_est[1] = 0.0f;
-
} else {
if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
if (landed_time == 0) {
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index cc0fb4155..b7f6509d7 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -116,7 +116,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
* @max 10.0
* @group Position Estimator INAV
*/
-PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 5.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 7.0f);
/**
* XY axis weight for vision velocity
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index c7e9ae3eb..bd777428f 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -33,6 +33,8 @@
#pragma once
+#include <inttypes.h>
+
/**
* @file protocol.h
*
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
index d4a00af39..91a9611d4 100644
--- a/src/modules/sdlog2/module.mk
+++ b/src/modules/sdlog2/module.mk
@@ -45,3 +45,6 @@ SRCS = sdlog2.c \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACFLAGS = -Wframe-larger-than=1300
+
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 6df677338..2daf73bf9 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -304,7 +304,7 @@ int sdlog2_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT - 30,
3000,
sdlog2_thread_main,
- (const char **)argv);
+ (char * const *)argv);
exit(0);
}
@@ -1089,6 +1089,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (_extended_logging) {
subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
+ } else {
+ subs.sat_info_sub = 0;
}
/* close non-needed fd's */
@@ -1110,6 +1112,7 @@ int sdlog2_thread_main(int argc, char *argv[])
hrt_abstime magnetometer_timestamp = 0;
hrt_abstime barometer_timestamp = 0;
hrt_abstime differential_pressure_timestamp = 0;
+ hrt_abstime barometer1_timestamp = 0;
hrt_abstime gyro1_timestamp = 0;
hrt_abstime accelerometer1_timestamp = 0;
hrt_abstime magnetometer1_timestamp = 0;
@@ -1255,6 +1258,7 @@ int sdlog2_thread_main(int argc, char *argv[])
bool write_IMU1 = false;
bool write_IMU2 = false;
bool write_SENS = false;
+ bool write_SENS1 = false;
if (buf.sensor.timestamp != gyro_timestamp) {
gyro_timestamp = buf.sensor.timestamp;
@@ -1305,6 +1309,22 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(SENS);
}
+ if (buf.sensor.baro1_timestamp != barometer1_timestamp) {
+ barometer1_timestamp = buf.sensor.baro1_timestamp;
+ write_SENS1 = true;
+ }
+
+ if (write_SENS1) {
+ log_msg.msg_type = LOG_AIR1_MSG;
+ log_msg.body.log_SENS.baro_pres = buf.sensor.baro1_pres_mbar;
+ log_msg.body.log_SENS.baro_alt = buf.sensor.baro1_alt_meter;
+ log_msg.body.log_SENS.baro_temp = buf.sensor.baro1_temp_celcius;
+ log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure1_pa;
+ log_msg.body.log_SENS.diff_pres_filtered = buf.sensor.differential_pressure1_filtered_pa;
+ // XXX moving to AIR0-AIR2 instead of SENS
+ LOGBUFFER_WRITE_AND_COUNT(SENS);
+ }
+
if (buf.sensor.accelerometer1_timestamp != accelerometer1_timestamp) {
accelerometer1_timestamp = buf.sensor.accelerometer1_timestamp;
write_IMU1 = true;
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index b78b430aa..5941bfac0 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -424,6 +424,9 @@ struct log_ENCD_s {
float vel1;
};
+/* --- AIR SPEED SENSORS - DIFF. PRESSURE --- */
+#define LOG_AIR1_MSG 40
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -457,7 +460,8 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT_S(IMU, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT_S(IMU1, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
- LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
+ LOG_FORMAT_S(SENS, SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
+ LOG_FORMAT_S(AIR1, SENS, "fffff", "BaroPa,BaroAlt,BaroTmp,DiffPres,DiffPresF"),
LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"),
@@ -468,7 +472,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/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp
index 061fbf9b9..ee492f85a 100644
--- a/src/modules/segway/segway_main.cpp
+++ b/src/modules/segway/segway_main.cpp
@@ -110,7 +110,7 @@ int segway_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
5120,
segway_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index dfbba92d9..f37bc9327 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -44,3 +44,5 @@ SRCS = sensors.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-type-limits
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 229bfe3ce..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
@@ -747,6 +766,41 @@ PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */
*/
PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
+/**
+ * Channel which changes a parameter
+ *
+ * Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.
+ * Set to 0 to deactivate *
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_PARAM1, 0);
+
+/**
+ * Channel which changes a parameter
+ *
+ * Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.
+ * Set to 0 to deactivate *
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_PARAM2, 0);
+
+/**
+ * Channel which changes a parameter
+ *
+ * Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.
+ * Set to 0 to deactivate *
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0);
/**
* Failsafe channel PWM threshold.
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index cdcb428dd..2c798af3b 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -37,7 +37,7 @@
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -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>
@@ -82,6 +83,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/airspeed.h>
+#include <uORB/topics/rc_parameter_map.h>
#define GYRO_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */
#define ACC_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */
@@ -191,6 +193,14 @@ private:
switch_pos_t get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv);
/**
+ * Update paramters from RC channels if the functionality is activated and the
+ * input has changed since the last update
+ *
+ * @param
+ */
+ void set_params_from_rc();
+
+ /**
* Gather and publish RC input data.
*/
void rc_poll();
@@ -216,10 +226,12 @@ private:
int _mag2_sub; /**< raw mag2 data subscription */
int _rc_sub; /**< raw rc channels data subscription */
int _baro_sub; /**< raw baro data subscription */
+ int _baro1_sub; /**< raw baro data subscription */
int _airspeed_sub; /**< airspeed subscription */
int _diff_pres_sub; /**< raw differential pressure subscription */
int _vcontrol_mode_sub; /**< vehicle control mode subscription */
int _params_sub; /**< notification of parameter updates */
+ int _rc_parameter_map_sub; /**< rc parameter map subscription */
int _manual_control_sub; /**< notification of manual control updates */
orb_advert_t _sensor_pub; /**< combined sensor data topic */
@@ -237,6 +249,7 @@ private:
struct baro_report _barometer; /**< barometer data */
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
+ struct rc_parameter_map_s _rc_parameter_map;
math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
@@ -263,6 +276,7 @@ private:
float diff_pres_analog_scale;
int board_rotation;
+ int flow_rotation;
int external_mag_rotation;
float board_offset[3];
@@ -288,6 +302,8 @@ private:
int rc_map_aux4;
int rc_map_aux5;
+ int rc_map_param[RC_PARAM_MAP_NCHAN];
+
int32_t rc_fails_thr;
float rc_assist_th;
float rc_auto_th;
@@ -348,6 +364,12 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
+ param_t rc_map_param[RC_PARAM_MAP_NCHAN];
+ param_t rc_param[RC_PARAM_MAP_NCHAN]; /**< param handles for the paramters which are bound
+ to a RC channel, equivalent float values in the
+ _parameters struct are not existing
+ because these parameters are never read. */
+
param_t rc_fails_thr;
param_t rc_assist_th;
param_t rc_auto_th;
@@ -361,6 +383,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];
@@ -378,27 +401,27 @@ private:
/**
* Do accel-related initialisation.
*/
- void accel_init();
+ int accel_init();
/**
* Do gyro-related initialisation.
*/
- void gyro_init();
+ int gyro_init();
/**
* Do mag-related initialisation.
*/
- void mag_init();
+ int mag_init();
/**
* Do baro-related initialisation.
*/
- void baro_init();
+ int baro_init();
/**
* Do adc-related initialisation.
*/
- void adc_init();
+ int adc_init();
/**
* Poll the accelerometer for updated data.
@@ -451,6 +474,11 @@ private:
void parameter_update_poll(bool forced = false);
/**
+ * Check for changes in rc_parameter_map
+ */
+ void rc_parameter_map_poll(bool forced = false);
+
+ /**
* Poll the ADC and update readings to suit.
*
* @param raw Combined sensor data structure into which
@@ -479,7 +507,7 @@ Sensors::Sensors() :
_fd_adc(-1),
_last_adc(0),
- _task_should_exit(false),
+ _task_should_exit(true),
_sensors_task(-1),
_hil_enabled(false),
_publishing(true),
@@ -496,8 +524,10 @@ Sensors::Sensors() :
_mag2_sub(-1),
_rc_sub(-1),
_baro_sub(-1),
+ _baro1_sub(-1),
_vcontrol_mode_sub(-1),
_params_sub(-1),
+ _rc_parameter_map_sub(-1),
_manual_control_sub(-1),
/* publications */
@@ -518,6 +548,7 @@ Sensors::Sensors() :
{
memset(&_rc, 0, sizeof(_rc));
memset(&_diff_pres, 0, sizeof(_diff_pres));
+ memset(&_rc_parameter_map, 0, sizeof(_rc_parameter_map));
/* basic r/c parameters */
for (unsigned i = 0; i < _rc_max_chan_count; i++) {
@@ -570,6 +601,13 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
+ /* RC to parameter mapping for changing parameters with RC */
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ char name[PARAM_ID_LEN];
+ snprintf(name, PARAM_ID_LEN, "RC_MAP_PARAM%d", i + 1); // shifted by 1 because param name starts at 1
+ _parameter_handles.rc_map_param[i] = param_find(name);
+ }
+
/* RC thresholds */
_parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
_parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
@@ -614,6 +652,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 */
@@ -747,6 +786,9 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ param_get(_parameter_handles.rc_map_param[i], &(_parameters.rc_map_param[i]));
+ }
param_get(_parameter_handles.rc_fails_thr, &(_parameters.rc_fails_thr));
param_get(_parameter_handles.rc_assist_th, &(_parameters.rc_assist_th));
_parameters.rc_assist_inv = (_parameters.rc_assist_th < 0);
@@ -791,6 +833,10 @@ Sensors::parameters_update()
_rc.function[AUX_4] = _parameters.rc_map_aux4 - 1;
_rc.function[AUX_5] = _parameters.rc_map_aux5 - 1;
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ _rc.function[PARAM_1 + i] = _parameters.rc_map_param[i] - 1;
+ }
+
/* gyro offsets */
param_get(_parameter_handles.gyro_offset[0], &(_parameters.gyro_offset[0]));
param_get(_parameter_handles.gyro_offset[1], &(_parameters.gyro_offset[1]));
@@ -831,8 +877,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);
@@ -850,26 +910,26 @@ 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) {
- warn("%s", BARO_DEVICE_PATH);
- errx(1, "FATAL: no barometer found");
+ int barofd;
+ barofd = open(BARO_DEVICE_PATH, 0);
+ if (barofd < 0) {
+ warnx("ERROR: no barometer foundon %s", BARO_DEVICE_PATH);
+ return ERROR;
} 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;
}
-void
+int
Sensors::accel_init()
{
int fd;
@@ -877,8 +937,8 @@ Sensors::accel_init()
fd = open(ACCEL_DEVICE_PATH, 0);
if (fd < 0) {
- warn("%s", ACCEL_DEVICE_PATH);
- errx(1, "FATAL: no accelerometer found");
+ warnx("FATAL: no accelerometer found: %s", ACCEL_DEVICE_PATH);
+ return ERROR;
} else {
@@ -907,9 +967,11 @@ Sensors::accel_init()
close(fd);
}
+
+ return OK;
}
-void
+int
Sensors::gyro_init()
{
int fd;
@@ -917,8 +979,8 @@ Sensors::gyro_init()
fd = open(GYRO_DEVICE_PATH, 0);
if (fd < 0) {
- warn("%s", GYRO_DEVICE_PATH);
- errx(1, "FATAL: no gyro found");
+ warnx("FATAL: no gyro found: %s", GYRO_DEVICE_PATH);
+ return ERROR;
} else {
@@ -948,9 +1010,11 @@ Sensors::gyro_init()
close(fd);
}
+
+ return OK;
}
-void
+int
Sensors::mag_init()
{
int fd;
@@ -959,8 +1023,8 @@ Sensors::mag_init()
fd = open(MAG_DEVICE_PATH, 0);
if (fd < 0) {
- warn("%s", MAG_DEVICE_PATH);
- errx(1, "FATAL: no magnetometer found");
+ warnx("FATAL: no magnetometer found: %s", MAG_DEVICE_PATH);
+ return ERROR;
}
/* try different mag sampling rates */
@@ -981,7 +1045,8 @@ Sensors::mag_init()
ioctl(fd, SENSORIOCSPOLLRATE, 100);
} else {
- errx(1, "FATAL: mag sampling rate could not be set");
+ warnx("FATAL: mag sampling rate could not be set");
+ return ERROR;
}
}
@@ -990,7 +1055,8 @@ Sensors::mag_init()
ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
if (ret < 0) {
- errx(1, "FATAL: unknown if magnetometer is external or onboard");
+ warnx("FATAL: unknown if magnetometer is external or onboard");
+ return ERROR;
} else if (ret == 1) {
_mag_is_external = true;
@@ -1000,9 +1066,11 @@ Sensors::mag_init()
}
close(fd);
+
+ return OK;
}
-void
+int
Sensors::baro_init()
{
int fd;
@@ -1010,26 +1078,30 @@ Sensors::baro_init()
fd = open(BARO_DEVICE_PATH, 0);
if (fd < 0) {
- warn("%s", BARO_DEVICE_PATH);
- errx(1, "FATAL: No barometer found");
+ warnx("FATAL: No barometer found: %s", BARO_DEVICE_PATH);
+ return ERROR;
}
/* set the driver to poll at 150Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 150);
close(fd);
+
+ return OK;
}
-void
+int
Sensors::adc_init()
{
_fd_adc = open(ADC_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
if (_fd_adc < 0) {
- warn(ADC_DEVICE_PATH);
- warnx("FATAL: no ADC found");
+ warnx("FATAL: no ADC found: %s", ADC_DEVICE_PATH);
+ return ERROR;
}
+
+ return OK;
}
void
@@ -1200,6 +1272,34 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer_timestamp = mag_report.timestamp;
}
+
+ orb_check(_mag1_sub, &mag_updated);
+
+ if (mag_updated) {
+ struct mag_report mag_report;
+
+ orb_copy(ORB_ID(sensor_mag1), _mag1_sub, &mag_report);
+
+ raw.magnetometer1_raw[0] = mag_report.x_raw;
+ raw.magnetometer1_raw[1] = mag_report.y_raw;
+ raw.magnetometer1_raw[2] = mag_report.z_raw;
+
+ raw.magnetometer1_timestamp = mag_report.timestamp;
+ }
+
+ orb_check(_mag2_sub, &mag_updated);
+
+ if (mag_updated) {
+ struct mag_report mag_report;
+
+ orb_copy(ORB_ID(sensor_mag2), _mag2_sub, &mag_report);
+
+ raw.magnetometer2_raw[0] = mag_report.x_raw;
+ raw.magnetometer2_raw[1] = mag_report.y_raw;
+ raw.magnetometer2_raw[2] = mag_report.z_raw;
+
+ raw.magnetometer2_timestamp = mag_report.timestamp;
+ }
}
void
@@ -1218,6 +1318,21 @@ Sensors::baro_poll(struct sensor_combined_s &raw)
raw.baro_timestamp = _barometer.timestamp;
}
+
+ orb_check(_baro1_sub, &baro_updated);
+
+ if (baro_updated) {
+
+ struct baro_report baro_report;
+
+ orb_copy(ORB_ID(sensor_baro1), _baro1_sub, &baro_report);
+
+ raw.baro1_pres_mbar = baro_report.pressure; // Pressure in mbar
+ raw.baro1_alt_meter = baro_report.altitude; // Altitude in meters
+ raw.baro1_temp_celcius = baro_report.temperature; // Temperature in degrees celcius
+
+ raw.baro1_timestamp = baro_report.timestamp;
+ }
}
void
@@ -1374,6 +1489,45 @@ Sensors::parameter_update_poll(bool forced)
}
void
+Sensors::rc_parameter_map_poll(bool forced)
+{
+ bool map_updated;
+ orb_check(_rc_parameter_map_sub, &map_updated);
+
+ if (map_updated) {
+ orb_copy(ORB_ID(rc_parameter_map), _rc_parameter_map_sub, &_rc_parameter_map);
+ /* update paramter handles to which the RC channels are mapped */
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ if (_rc.function[PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
+ /* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
+ * or no request to map this channel to a param has been sent via mavlink
+ */
+ continue;
+ }
+
+ /* Set the handle by index if the index is set, otherwise use the id */
+ if (_rc_parameter_map.param_index[i] >= 0) {
+ _parameter_handles.rc_param[i] = param_for_index((unsigned)_rc_parameter_map.param_index[i]);
+ } else {
+ _parameter_handles.rc_param[i] = param_find(_rc_parameter_map.param_id[i]);
+ }
+
+ }
+ warnx("rc to parameter map updated");
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ warnx("\ti %d param_id %s scale %.3f value0 %.3f, min %.3f, max %.3f",
+ i,
+ _rc_parameter_map.param_id[i],
+ (double)_rc_parameter_map.scale[i],
+ (double)_rc_parameter_map.value0[i],
+ (double)_rc_parameter_map.value_min[i],
+ (double)_rc_parameter_map.value_max[i]
+ );
+ }
+ }
+}
+
+void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
/* only read if publishing */
@@ -1552,6 +1706,31 @@ Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, boo
}
void
+Sensors::set_params_from_rc()
+{
+ static float param_rc_values[RC_PARAM_MAP_NCHAN] = {};
+ for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ if (_rc.function[PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
+ /* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
+ * or no request to map this channel to a param has been sent via mavlink
+ */
+ continue;
+ }
+
+ float rc_val = get_rc_value((enum RC_CHANNELS_FUNCTION)(PARAM_1 + i), -1.0, 1.0);
+ /* Check if the value has changed,
+ * maybe we need to introduce a more aggressive limit here */
+ if (rc_val > param_rc_values[i] + FLT_EPSILON || rc_val < param_rc_values[i] - FLT_EPSILON) {
+ param_rc_values[i] = rc_val;
+ float param_val = math::constrain(
+ _rc_parameter_map.value0[i] + _rc_parameter_map.scale[i] * rc_val,
+ _rc_parameter_map.value_min[i], _rc_parameter_map.value_max[i]);
+ param_set(_parameter_handles.rc_param[i], &param_val);
+ }
+ }
+}
+
+void
Sensors::rc_poll()
{
bool rc_updated;
@@ -1717,6 +1896,13 @@ Sensors::rc_poll()
} else {
_actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3);
}
+
+ /* Update parameters from RC Channels (tuning with RC) if activated */
+ static hrt_abstime last_rc_to_param_map_time = 0;
+ if (hrt_elapsed_time(&last_rc_to_param_map_time) > 1e6) {
+ set_params_from_rc();
+ last_rc_to_param_map_time = hrt_absolute_time();
+ }
}
}
}
@@ -1732,11 +1918,27 @@ Sensors::task_main()
{
/* start individual sensors */
- accel_init();
- gyro_init();
- mag_init();
- baro_init();
- adc_init();
+ int ret;
+ ret = accel_init();
+ if (ret) {
+ goto exit_immediate;
+ }
+ ret = gyro_init();
+ if (ret) {
+ goto exit_immediate;
+ }
+ ret = mag_init();
+ if (ret) {
+ goto exit_immediate;
+ }
+ ret = baro_init();
+ if (ret) {
+ goto exit_immediate;
+ }
+ ret = adc_init();
+ if (ret) {
+ goto exit_immediate;
+ }
/*
* do subscriptions
@@ -1752,9 +1954,11 @@ Sensors::task_main()
_mag2_sub = orb_subscribe(ORB_ID(sensor_mag2));
_rc_sub = orb_subscribe(ORB_ID(input_rc));
_baro_sub = orb_subscribe(ORB_ID(sensor_baro0));
+ _baro1_sub = orb_subscribe(ORB_ID(sensor_baro1));
_diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
+ _rc_parameter_map_sub = orb_subscribe(ORB_ID(rc_parameter_map));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
/* rate limit vehicle status updates to 5Hz */
@@ -1788,6 +1992,7 @@ Sensors::task_main()
diff_pres_poll(raw);
parameter_update_poll(true /* forced */);
+ rc_parameter_map_poll(true /* forced */);
/* advertise the sensor_combined topic and make the initial publication */
_sensor_pub = orb_advertise(ORB_ID(sensor_combined), &raw);
@@ -1799,6 +2004,8 @@ Sensors::task_main()
fds[0].fd = _gyro_sub;
fds[0].events = POLLIN;
+ _task_should_exit = false;
+
while (!_task_should_exit) {
/* wait for up to 50ms for data */
@@ -1820,6 +2027,9 @@ Sensors::task_main()
/* check parameters for updates */
parameter_update_poll();
+ /* check rc parameter map for updates */
+ rc_parameter_map_poll();
+
/* the timestamp of the raw struct is updated by the gyro_poll() method */
/* copy most recent sensor data */
@@ -1846,8 +2056,9 @@ Sensors::task_main()
warnx("[sensors] exiting.");
+exit_immediate:
_sensors_task = -1;
- _exit(0);
+ _exit(ret);
}
int
@@ -1863,9 +2074,13 @@ Sensors::start()
(main_t)&Sensors::task_main_trampoline,
nullptr);
+ /* wait until the task is up and running or has failed */
+ while(_sensors_task > 0 && _task_should_exit) {
+ usleep(100);
+ }
+
if (_sensors_task < 0) {
- warn("task start failed");
- return -errno;
+ return -ERROR;
}
return OK;
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index fe8b7e75a..f4dff2838 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -57,3 +57,5 @@ SRCS = err.c \
mcu_version.c
MAXOPTIMIZATION = -Os
+
+EXTRACFLAGS = -Wno-sign-compare
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index d6d8284d2..f9e90652d 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -41,7 +41,7 @@
#include <stdio.h>
#include <sys/queue.h>
#include <drivers/drv_hrt.h>
-
+#include <math.h>
#include "perf_counter.h"
/**
@@ -84,7 +84,8 @@ struct perf_ctr_interval {
uint64_t time_last;
uint64_t time_least;
uint64_t time_most;
-
+ float mean;
+ float M2;
};
/**
@@ -109,6 +110,7 @@ perf_alloc(enum perf_counter_type type, const char *name)
case PC_INTERVAL:
ctr = (perf_counter_t)calloc(sizeof(struct perf_ctr_interval), 1);
+
break;
default:
@@ -156,15 +158,23 @@ perf_count(perf_counter_t handle)
case 1:
pci->time_least = now - pci->time_last;
pci->time_most = now - pci->time_last;
+ pci->mean = pci->time_least / 1e6f;
+ pci->M2 = 0;
break;
default: {
- hrt_abstime interval = now - pci->time_last;
- if (interval < pci->time_least)
- pci->time_least = interval;
- if (interval > pci->time_most)
- pci->time_most = interval;
- break;
- }
+ hrt_abstime interval = now - pci->time_last;
+ if (interval < pci->time_least)
+ pci->time_least = interval;
+ if (interval > pci->time_most)
+ pci->time_most = interval;
+ // maintain mean and variance of interval in seconds
+ // Knuth/Welford recursive mean and variance of update intervals (via Wikipedia)
+ float dt = interval / 1e6f;
+ float delta_intvl = dt - pci->mean;
+ pci->mean += delta_intvl / pci->event_count;
+ pci->M2 += delta_intvl * (dt - pci->mean);
+ break;
+ }
}
pci->time_last = now;
pci->event_count++;
@@ -313,13 +323,16 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
case PC_INTERVAL: {
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
+ float rms = sqrtf(pci->M2 / (pci->event_count-1));
- dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus %5.3f msec mean %5.3f msec rms\n",
handle->name,
pci->event_count,
(pci->time_last - pci->time_first) / pci->event_count,
pci->time_least,
- pci->time_most);
+ pci->time_most,
+ (double)(1000 * pci->mean),
+ (double)(1000 * rms));
break;
}
@@ -365,6 +378,21 @@ perf_print_all(int fd)
}
}
+extern const uint16_t latency_bucket_count;
+extern uint32_t latency_counters[];
+extern const uint16_t latency_buckets[];
+
+void
+perf_print_latency(int fd)
+{
+ dprintf(fd, "bucket : events\n");
+ for (int i = 0; i < latency_bucket_count; i++) {
+ printf(" %4i : %i\n", latency_buckets[i], latency_counters[i]);
+ }
+ // print the overflow bucket value
+ dprintf(fd, " >%4i : %i\n", latency_buckets[latency_bucket_count-1], latency_counters[latency_bucket_count]);
+}
+
void
perf_reset_all(void)
{
@@ -374,4 +402,7 @@ perf_reset_all(void)
perf_reset(handle);
handle = (perf_counter_t)sq_next(&handle->link);
}
+ for (int i = 0; i <= latency_bucket_count; i++) {
+ latency_counters[i] = 0;
+ }
}
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index 668d9dfdf..d06606a5d 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -94,7 +94,7 @@ __EXPORT extern void perf_begin(perf_counter_t handle);
* End a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
- * If a call is made without a corresopnding perf_begin call, or if perf_cancel
+ * If a call is made without a corresponding perf_begin call, or if perf_cancel
* has been called subsequently, no change is made to the counter.
*
* @param handle The handle returned from perf_alloc.
@@ -143,6 +143,13 @@ __EXPORT extern void perf_print_counter_fd(int fd, perf_counter_t handle);
__EXPORT extern void perf_print_all(int fd);
/**
+ * Print hrt latency counters.
+ *
+ * @param fd File descriptor to print to - e.g. 0 for stdout
+ */
+__EXPORT extern void perf_print_latency(int fd);
+
+/**
* Reset all of the performance counters.
*/
__EXPORT extern void perf_reset_all(void);
diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c
index 702e435ac..a0988035c 100644
--- a/src/modules/systemlib/system_params.c
+++ b/src/modules/systemlib/system_params.c
@@ -82,3 +82,17 @@ PARAM_DEFINE_INT32(SYS_USE_IO, 1);
* @group System
*/
PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
+
+/**
+* Companion computer interface
+*
+* Configures the baud rate of the companion computer interface.
+* Set to zero to disable, set to 921600 to enable.
+* CURRENTLY ONLY SUPPORTS 921600 BAUD! Use extras.txt for
+* other baud rates.
+*
+* @min 0
+* @max 921600
+* @group System
+*/
+PARAM_DEFINE_INT32(SYS_COMPANION, 0);
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 90d8dd77c..82183b0d7 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -87,7 +87,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
kill(tcb->pid, SIGUSR1);
}
-int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
+int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
{
int pid;
diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h
index 6e22a557e..2f24215a9 100644
--- a/src/modules/systemlib/systemlib.h
+++ b/src/modules/systemlib/systemlib.h
@@ -64,7 +64,7 @@ __EXPORT int task_spawn_cmd(const char *name,
int scheduler,
int stack_size,
main_t entry,
- const char *argv[]);
+ char * const argv[]);
enum MULT_PORTS {
MULT_0_US2_RXTX = 0,
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 1141431cc..293412455 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -63,6 +63,7 @@ ORB_DEFINE(sensor_gyro2, struct gyro_report);
#include <drivers/drv_baro.h>
ORB_DEFINE(sensor_baro0, struct baro_report);
ORB_DEFINE(sensor_baro1, struct baro_report);
+ORB_DEFINE(sensor_baro2, struct baro_report);
#include <drivers/drv_range_finder.h>
ORB_DEFINE(sensor_range_finder, struct range_finder_report);
@@ -148,6 +149,9 @@ ORB_DEFINE(onboard_mission, struct mission_s);
#include "topics/mission_result.h"
ORB_DEFINE(mission_result, struct mission_result_s);
+#include "topics/geofence_result.h"
+ORB_DEFINE(geofence_result, struct geofence_result_s);
+
#include "topics/fence.h"
ORB_DEFINE(fence, unsigned);
@@ -243,3 +247,6 @@ ORB_DEFINE(tecs_status, struct tecs_status_s);
#include "topics/wind_estimate.h"
ORB_DEFINE(wind_estimate, struct wind_estimate_s);
+
+#include "topics/rc_parameter_map.h"
+ORB_DEFINE(rc_parameter_map, struct rc_parameter_map_s);
diff --git a/src/modules/uORB/topics/geofence_result.h b/src/modules/uORB/topics/geofence_result.h
new file mode 100644
index 000000000..b07e04499
--- /dev/null
+++ b/src/modules/uORB/topics/geofence_result.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file geofence_result.h
+ * Status of the plance concerning the geofence
+ *
+ * @author Ban Siesta <bansiesta@gmail.com>
+ */
+
+#ifndef TOPIC_GEOFENCE_RESULT_H
+#define TOPIC_GEOFENCE_RESULT_H
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct geofence_result_s
+{
+ bool geofence_violated; /**< true if the geofence is violated */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(geofence_result);
+
+#endif
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index c7d25d1f0..2ddc529a3 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,11 @@
/**
* @file mission_result.h
* Mission results that navigator needs to pass on to commander and mavlink.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Ban Siesta <bansiesta@gmail.com>
*/
#ifndef TOPIC_MISSION_RESULT_H
@@ -58,8 +60,10 @@ struct mission_result_s
bool reached; /**< true if mission has been reached */
bool finished; /**< true if mission has been completed */
bool stay_in_failsafe; /**< true if the commander should not switch out of the failsafe mode*/
- bool geofence_violated; /**< true if the geofence is violated */
bool flight_termination; /**< true if the navigator demands a flight termination from the commander app */
+ bool item_do_jump_changed; /**< true if the number of do jumps remaining has changed */
+ unsigned item_changed_index; /**< indicate which item has changed */
+ unsigned item_do_jump_remaining;/**< set to the number of do jumps remaining for that item */
};
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 16916cc4d..2fde5d424 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -65,12 +65,15 @@ enum RC_CHANNELS_FUNCTION {
AUX_2,
AUX_3,
AUX_4,
- AUX_5
+ AUX_5,
+ PARAM_1,
+ PARAM_2,
+ PARAM_3
};
// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS
-#define RC_CHANNELS_FUNCTION_MAX 18
+#define RC_CHANNELS_FUNCTION_MAX 19
/**
* @addtogroup topics
diff --git a/src/modules/uORB/topics/rc_parameter_map.h b/src/modules/uORB/topics/rc_parameter_map.h
new file mode 100644
index 000000000..6e68dc4b6
--- /dev/null
+++ b/src/modules/uORB/topics/rc_parameter_map.h
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT ,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_parameter_map.h
+ * Maps RC channels to parameters
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef TOPIC_RC_PARAMETER_MAP_H
+#define TOPIC_RC_PARAMETER_MAP_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define RC_PARAM_MAP_NCHAN 3 // This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h
+#define PARAM_ID_LEN 16 // corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct rc_parameter_map_s {
+ uint64_t timestamp; /**< time at which the map was updated */
+
+ bool valid[RC_PARAM_MAP_NCHAN]; /**< true for RC-Param channels which are mapped to a param */
+
+ int param_index[RC_PARAM_MAP_NCHAN]; /**< corresponding param index, this
+ this field is ignored if set to -1, in this case param_id will
+ be used*/
+ char param_id[RC_PARAM_MAP_NCHAN][PARAM_ID_LEN + 1]; /**< corresponding param id, null terminated */
+ float scale[RC_PARAM_MAP_NCHAN]; /** scale to map the RC input [-1, 1] to a parameter value */
+ float value0[RC_PARAM_MAP_NCHAN]; /** inital value around which the parameter value is changed */
+ float value_min[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
+ float value_max[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
+};
+
+/**
+ * @}
+ */
+
+ORB_DECLARE(rc_parameter_map);
+
+#endif
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index 06dfcdab3..583a39ded 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -122,15 +122,25 @@ struct sensor_combined_s {
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */
float baro_temp_celcius; /**< Temperature in degrees celsius */
- float adc_voltage_v[10]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
+ uint64_t baro_timestamp; /**< Barometer timestamp */
+
+ float baro1_pres_mbar; /**< Barometric pressure, already temp. comp. */
+ float baro1_alt_meter; /**< Altitude, already temp. comp. */
+ float baro1_temp_celcius; /**< Temperature in degrees celsius */
+ uint64_t baro1_timestamp; /**< Barometer timestamp */
+
+ float adc_voltage_v[10]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
unsigned adc_mapping[10]; /**< Channel indices of each of these values */
float mcu_temp_celcius; /**< Internal temperature measurement of MCU */
- uint64_t baro_timestamp; /**< Barometer timestamp */
- float differential_pressure_pa; /**< Airspeed sensor differential pressure */
- uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */
+ float differential_pressure_pa; /**< Airspeed sensor differential pressure */
+ uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */
float differential_pressure_filtered_pa; /**< Low pass filtered airspeed sensor differential pressure reading */
+ float differential_pressure1_pa; /**< Airspeed sensor differential pressure */
+ uint64_t differential_pressure1_timestamp; /**< Last measurement timestamp */
+ float differential_pressure1_filtered_pa; /**< Low pass filtered airspeed sensor differential pressure reading */
+
};
/**
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/uORB/uORB.h b/src/modules/uORB/uORB.h
index 82ff46ad2..beb23f61d 100644
--- a/src/modules/uORB/uORB.h
+++ b/src/modules/uORB/uORB.h
@@ -68,6 +68,33 @@ typedef const struct orb_metadata *orb_id_t;
#define ORB_ID(_name) &__orb_##_name
/**
+ * Generates a pointer to the uORB metadata structure for
+ * a given topic.
+ *
+ * The topic must have been declared previously in scope
+ * with ORB_DECLARE().
+ *
+ * @param _name The name of the topic.
+ * @param _count The class ID of the topic
+ */
+#define ORB_ID_DOUBLE(_name, _count) ((_count == CLASS_DEVICE_PRIMARY) ? &__orb_##_name##0 : &__orb_##_name##1)
+
+/**
+ * Generates a pointer to the uORB metadata structure for
+ * a given topic.
+ *
+ * The topic must have been declared previously in scope
+ * with ORB_DECLARE().
+ *
+ * @param _name The name of the topic.
+ * @param _count The class ID of the topic
+ */
+#define ORB_ID_TRIPLE(_name, _count) \
+ ((_count == CLASS_DEVICE_PRIMARY) ? &__orb_##_name##0 : \
+ ((_count == CLASS_DEVICE_SECONDARY) ? &__orb_##_name##1 : \
+ (((_count == CLASS_DEVICE_TERTIARY) ? &__orb_##_name##2 : 0))))
+
+/**
* Declare (prototype) the uORB metadata for a topic.
*
* Note that optional topics are declared weak; this allows a potential
diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk
index f92bc754f..e5d30f6c4 100644
--- a/src/modules/uavcan/module.mk
+++ b/src/modules/uavcan/module.mk
@@ -57,7 +57,7 @@ SRCS += sensors/sensor_bridge.cpp \
#
# libuavcan
#
-include $(UAVCAN_DIR)/libuavcan/include.mk
+include $(PX4_LIB_DIR)/uavcan/libuavcan/include.mk
SRCS += $(LIBUAVCAN_SRC)
INCLUDE_DIRS += $(LIBUAVCAN_INC)
# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
@@ -67,7 +67,7 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAV
#
# libuavcan drivers for STM32
#
-include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk
+include $(PX4_LIB_DIR)/uavcan/libuavcan_drivers/stm32/driver/include.mk
SRCS += $(LIBUAVCAN_STM32_SRC)
INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2
diff --git a/src/modules/vtol_att_control/module.mk b/src/modules/vtol_att_control/module.mk
index 0d5155e90..0cf3072c8 100644
--- a/src/modules/vtol_att_control/module.mk
+++ b/src/modules/vtol_att_control/module.mk
@@ -39,3 +39,6 @@ MODULE_COMMAND = vtol_att_control
SRCS = vtol_att_control_main.cpp \
vtol_att_control_params.c
+
+EXTRACXXFLAGS = -Wno-write-strings
+
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 958907d1b..c72a85ecd 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -74,11 +74,8 @@
#include <lib/geo/geo.h>
#include "drivers/drv_pwm_output.h"
-#include <nuttx/fs/nxffs.h>
#include <nuttx/fs/ioctl.h>
-#include <nuttx/mtd.h>
-
#include <fcntl.h>
@@ -137,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 */
@@ -237,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();
@@ -414,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;
@@ -426,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;
}
@@ -455,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
@@ -600,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;
@@ -650,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);
+
diff --git a/src/systemcmds/bl_update/bl_update.c b/src/systemcmds/bl_update/bl_update.c
index 0569d89f5..ec9269d39 100644
--- a/src/systemcmds/bl_update/bl_update.c
+++ b/src/systemcmds/bl_update/bl_update.c
@@ -52,6 +52,8 @@
#include "systemlib/systemlib.h"
#include "systemlib/err.h"
+#define BL_FILE_SIZE_LIMIT 16384
+
__EXPORT int bl_update_main(int argc, char *argv[]);
static void setopt(void);
@@ -72,12 +74,12 @@ bl_update_main(int argc, char *argv[])
struct stat s;
- if (stat(argv[1], &s) < 0)
+ if (!stat(argv[1], &s))
err(1, "stat %s", argv[1]);
/* sanity-check file size */
- if (s.st_size > 16384)
- errx(1, "%s: file too large", argv[1]);
+ if (s.st_size > BL_FILE_SIZE_LIMIT)
+ errx(1, "%s: file too large (limit: %u, actual: %d)", argv[1], BL_FILE_SIZE_LIMIT, s.st_size);
uint8_t *buf = malloc(s.st_size);
diff --git a/src/systemcmds/mixer/module.mk b/src/systemcmds/mixer/module.mk
index cdbff75f0..0fb899c67 100644
--- a/src/systemcmds/mixer/module.mk
+++ b/src/systemcmds/mixer/module.mk
@@ -41,3 +41,6 @@ SRCS = mixer.cpp
MODULE_STACKSIZE = 4096
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wframe-larger-than=2048
+
diff --git a/src/systemcmds/mtd/module.mk b/src/systemcmds/mtd/module.mk
index 1bc4f414e..bca1cdcc1 100644
--- a/src/systemcmds/mtd/module.mk
+++ b/src/systemcmds/mtd/module.mk
@@ -6,3 +6,6 @@ MODULE_COMMAND = mtd
SRCS = mtd.c 24xxxx_mtd.c
MAXOPTIMIZATION = -Os
+
+EXTRACFLAGS = -Wno-error
+
diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c
index e110335e7..80ee204e8 100644
--- a/src/systemcmds/param/param.c
+++ b/src/systemcmds/param/param.c
@@ -212,7 +212,7 @@ static void
do_show(const char* search_string)
{
printf(" + = saved, * = unsaved\n");
- param_foreach(do_show_print, search_string, false);
+ param_foreach(do_show_print, (char *)search_string, false);
exit(0);
}
diff --git a/src/systemcmds/perf/perf.c b/src/systemcmds/perf/perf.c
index b08a2e3b7..a788dfc11 100644
--- a/src/systemcmds/perf/perf.c
+++ b/src/systemcmds/perf/perf.c
@@ -68,8 +68,12 @@ int perf_main(int argc, char *argv[])
if (strcmp(argv[1], "reset") == 0) {
perf_reset_all();
return 0;
+ } else if (strcmp(argv[1], "latency") == 0) {
+ perf_print_latency(0 /* stdout */);
+ fflush(stdout);
+ return 0;
}
- printf("Usage: perf <reset>\n");
+ printf("Usage: perf [reset | latency]\n");
return -1;
}
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 622a0faf3..0dc333f0a 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -34,3 +34,6 @@ SRCS = test_adc.c \
test_conv.cpp \
test_mount.c \
test_mtd.c
+
+EXTRACXXFLAGS = -Wframe-larger-than=2500 -Wno-float-equal -Wno-double-promotion
+
diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp
index 70d173fc9..9fa52aaaa 100644
--- a/src/systemcmds/tests/test_mathlib.cpp
+++ b/src/systemcmds/tests/test_mathlib.cpp
@@ -54,6 +54,7 @@ using namespace math;
int test_mathlib(int argc, char *argv[])
{
+ int rc = 0;
warnx("testing mathlib");
{
@@ -156,5 +157,53 @@ int test_mathlib(int argc, char *argv[])
TEST_OP("Matrix<10, 10> * Matrix<10, 10>", m1 * m2);
}
- return 0;
+ {
+ // test nonsymmetric +, -, +=, -=
+
+ float data1[2][3] = {{1,2,3},{4,5,6}};
+ float data2[2][3] = {{2,4,6},{8,10,12}};
+ float data3[2][3] = {{3,6,9},{12,15,18}};
+
+ Matrix<2, 3> m1(data1);
+ Matrix<2, 3> m2(data2);
+ Matrix<2, 3> m3(data3);
+
+ if (m1 + m2 != m3) {
+ warnx("Matrix<2, 3> + Matrix<2, 3> failed!");
+ (m1 + m2).print();
+ printf("!=\n");
+ m3.print();
+ rc = 1;
+ }
+
+ if (m3 - m2 != m1) {
+ warnx("Matrix<2, 3> - Matrix<2, 3> failed!");
+ (m3 - m2).print();
+ printf("!=\n");
+ m1.print();
+ rc = 1;
+ }
+
+ m1 += m2;
+ if (m1 != m3) {
+ warnx("Matrix<2, 3> += Matrix<2, 3> failed!");
+ m1.print();
+ printf("!=\n");
+ m3.print();
+ rc = 1;
+ }
+
+ m1 -= m2;
+ Matrix<2, 3> m1_orig(data1);
+ if (m1 != m1_orig) {
+ warnx("Matrix<2, 3> -= Matrix<2, 3> failed!");
+ m1.print();
+ printf("!=\n");
+ m1_orig.print();
+ rc = 1;
+ }
+
+ }
+
+ return rc;
}