aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/drivers/batt_smbus/batt_smbus.cpp540
-rw-r--r--src/drivers/batt_smbus/module.mk8
-rw-r--r--src/drivers/device/i2c.h2
-rw-r--r--src/drivers/drv_batt_smbus.h47
-rw-r--r--src/drivers/px4flow/px4flow.cpp11
-rw-r--r--src/modules/commander/module.mk2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp23
-rw-r--r--src/modules/mavlink/module.mk4
-rw-r--r--src/modules/navigator/navigator_params.c8
-rw-r--r--src/modules/navigator/rtl_params.c11
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h2
11 files changed, 634 insertions, 24 deletions
diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
new file mode 100644
index 000000000..dd83dacaf
--- /dev/null
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -0,0 +1,540 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Randy Mackay <rmackay9@yahoo.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file batt_smbus.cpp
+ *
+ * Driver for a battery monitor connected via SMBus (I2C).
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <sched.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+#include <ctype.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <board_config.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/subsystem_info.h>
+#include <uORB/topics/battery_status.h>
+
+#include <float.h>
+
+#include <drivers/device/i2c.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_batt_smbus.h>
+#include <drivers/device/ringbuffer.h>
+
+#define BATT_SMBUS_ADDR_MIN 0x08 /* lowest possible address */
+#define BATT_SMBUS_ADDR_MAX 0x7F /* highest possible address */
+
+#define BATT_SMBUS_I2C_BUS PX4_I2C_BUS_EXPANSION
+#define BATT_SMBUS_ADDR 0x0B /* I2C address */
+#define BATT_SMBUS_TEMP 0x08 /* temperature register */
+#define BATT_SMBUS_VOLTAGE 0x09 /* voltage register */
+#define BATT_SMBUS_DESIGN_CAPACITY 0x18 /* design capacity register */
+#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 /* design voltage register */
+#define BATT_SMBUS_SERIALNUM 0x1c /* serial number register */
+#define BATT_SMBUS_MANUFACTURE_NAME 0x20 /* manufacturer name */
+#define BATT_SMBUS_MANUFACTURE_INFO 0x25 /* cell voltage register */
+#define BATT_SMBUS_CURRENT 0x2a /* current register */
+#define BATT_SMBUS_MEASUREMENT_INTERVAL_MS (1000000 / 10) /* time in microseconds, measure at 10hz */
+
+#define BATT_SMBUS_PEC_POLYNOMIAL 0x07 /* Polynomial for calculating PEC */
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class BATT_SMBUS : public device::I2C
+{
+public:
+ BATT_SMBUS(int bus = PX4_I2C_BUS_EXPANSION, uint16_t batt_smbus_addr = BATT_SMBUS_ADDR);
+ virtual ~BATT_SMBUS();
+
+ virtual int init();
+ virtual int test();
+ int search(); /* search all possible slave addresses for a smart battery */
+
+protected:
+ virtual int probe(); // check if the device can be contacted
+
+private:
+
+ // start periodic reads from the battery
+ void start();
+
+ // stop periodic reads from the battery
+ void stop();
+
+ // static function that is called by worker queue
+ static void cycle_trampoline(void *arg);
+
+ // perform a read from the battery
+ void cycle();
+
+ // read_reg - read a word from specified register
+ int read_reg(uint8_t reg, uint16_t &val);
+
+ // read_block - returns number of characters read if successful, zero if unsuccessful
+ uint8_t read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero);
+
+ // get_PEC - calculate PEC for a read or write from the battery
+ // buff is the data that was read or will be written
+ uint8_t get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
+
+ // internal variables
+ work_s _work; // work queue for scheduling reads
+ RingBuffer *_reports; // buffer of recorded voltages, currents
+ struct battery_status_s _last_report; // last published report, used for test()
+ orb_advert_t _batt_topic;
+ orb_id_t _batt_orb_id;
+};
+
+/* for now, we only support one BATT_SMBUS */
+namespace
+{
+BATT_SMBUS *g_batt_smbus;
+}
+
+void batt_smbus_usage();
+
+extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);
+
+// constructor
+BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
+ I2C("batt_smbus", BATT_SMBUS_DEVICE_PATH, bus, batt_smbus_addr, 400000),
+ _work{},
+ _reports(nullptr),
+ _batt_topic(-1),
+ _batt_orb_id(nullptr)
+{
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+// destructor
+BATT_SMBUS::~BATT_SMBUS()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+}
+
+int
+BATT_SMBUS::init()
+{
+ int ret = ENOTTY;
+
+ // attempt to initialise I2C bus
+ ret = I2C::init();
+
+ if (ret != OK) {
+ errx(1,"failed to init I2C");
+ return ret;
+ } else {
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(struct battery_status_s));
+ if (_reports == nullptr) {
+ ret = ENOTTY;
+ } else {
+ // start work queue
+ start();
+ }
+ }
+
+ // init orb id
+ _batt_orb_id = ORB_ID(battery_status);
+
+ return ret;
+}
+
+int
+BATT_SMBUS::test()
+{
+ int sub = orb_subscribe(ORB_ID(battery_status));
+ bool updated = false;
+ struct battery_status_s status;
+ uint64_t start_time = hrt_absolute_time();
+
+ // loop for 5 seconds
+ while ((hrt_absolute_time() - start_time) < 5000000) {
+
+ // display new info that has arrived from the orb
+ orb_check(sub, &updated);
+ if (updated) {
+ if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
+ warnx("V=%4.2f C=%4.2f", status.voltage_v, status.current_a);
+ }
+ }
+
+ // sleep for 0.05 seconds
+ usleep(50000);
+ }
+
+ return OK;
+}
+
+/* search all possible slave addresses for a smart battery */
+int
+BATT_SMBUS::search()
+{
+ bool found_slave = false;
+ uint16_t tmp;
+
+ // search through all valid SMBus addresses
+ for (uint8_t i=BATT_SMBUS_ADDR_MIN; i<=BATT_SMBUS_ADDR_MAX; i++) {
+ set_address(i);
+ if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
+ warnx("battery found at 0x%x",(int)i);
+ found_slave = true;
+ }
+ // short sleep
+ usleep(1);
+ }
+
+ // display completion message
+ if (found_slave) {
+ warnx("Done.");
+ } else {
+ warnx("No smart batteries found.");
+ }
+
+ return OK;
+}
+
+int
+BATT_SMBUS::probe()
+{
+ // always return OK to ensure device starts
+ return OK;
+}
+
+// start periodic reads from the battery
+void
+BATT_SMBUS::start()
+{
+ /* reset the report ring and state machine */
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&BATT_SMBUS::cycle_trampoline, this, 1);
+}
+
+// stop periodic reads from the battery
+void
+BATT_SMBUS::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+// static function that is called by worker queue
+void
+BATT_SMBUS::cycle_trampoline(void *arg)
+{
+ BATT_SMBUS *dev = (BATT_SMBUS *)arg;
+
+ dev->cycle();
+}
+
+// perform a read from the battery
+void
+BATT_SMBUS::cycle()
+{
+ // read data from sensor
+ struct battery_status_s new_report;
+
+ // set time of reading
+ new_report.timestamp = hrt_absolute_time();
+
+ // read voltage
+ uint16_t tmp;
+ if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
+ // initialise new_report
+ memset(&new_report, 0, sizeof(new_report));
+
+ // convert millivolts to volts
+ new_report.voltage_v = ((float)tmp) / 1000.0f;
+
+ // read current
+ usleep(1);
+ uint8_t buff[4];
+ if (read_block(BATT_SMBUS_CURRENT, buff, 4, false) == 4) {
+ new_report.current_a = (float)((int32_t)((uint32_t)buff[3]<<24 | (uint32_t)buff[2]<<16 | (uint32_t)buff[1]<<8 | (uint32_t)buff[0])) / 1000.0f;
+ }
+
+ // publish to orb
+ if (_batt_topic != -1) {
+ orb_publish(_batt_orb_id, _batt_topic, &new_report);
+ } else {
+ _batt_topic = orb_advertise(_batt_orb_id, &new_report);
+ if (_batt_topic < 0) {
+ errx(1, "ADVERT FAIL");
+ }
+ }
+
+ // copy report for test()
+ _last_report = new_report;
+
+ /* post a report to the ring */
+ _reports->force(&new_report);
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+ }
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK, &_work, (worker_t)&BATT_SMBUS::cycle_trampoline, this, USEC2TICK(BATT_SMBUS_MEASUREMENT_INTERVAL_MS));
+}
+
+int
+BATT_SMBUS::read_reg(uint8_t reg, uint16_t &val)
+{
+ uint8_t buff[3]; // 2 bytes of data + PEC
+
+ // read from register
+ int ret = transfer(&reg, 1, buff, 3);
+ if (ret == OK) {
+ // check PEC
+ uint8_t pec = get_PEC(reg, true, buff, 2);
+ if (pec == buff[2]) {
+ val = (uint16_t)buff[1] << 8 | (uint16_t)buff[0];
+ } else {
+ ret = ENOTTY;
+ }
+ }
+
+ // return success or failure
+ return ret;
+}
+
+// read_block - returns number of characters read if successful, zero if unsuccessful
+uint8_t BATT_SMBUS::read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero)
+{
+ uint8_t buff[max_len+2]; // buffer to hold results
+
+ usleep(1);
+
+ // read bytes including PEC
+ int ret = transfer(&reg, 1, buff, max_len+2);
+
+ // return zero on failure
+ if (ret != OK) {
+ return 0;
+ }
+
+ // get length
+ uint8_t bufflen = buff[0];
+
+ // sanity check length returned by smbus
+ if (bufflen == 0 || bufflen > max_len) {
+ return 0;
+ }
+
+ // check PEC
+ uint8_t pec = get_PEC(reg, true, buff, bufflen+1);
+ if (pec != buff[bufflen+1]) {
+ // debug
+ warnx("CurrPEC:%x vs MyPec:%x",(int)buff[bufflen+1],(int)pec);
+ return 0;
+ } else {
+ warnx("CurPEC ok: %x",(int)pec);
+ }
+
+ // copy data
+ memcpy(data, &buff[1], bufflen);
+
+ // optionally add zero to end
+ if (append_zero) {
+ data[bufflen] = '\0';
+ }
+
+ // return success
+ return bufflen;
+}
+
+// get_PEC - calculate PEC for a read or write from the battery
+// buff is the data that was read or will be written
+uint8_t BATT_SMBUS::get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const
+{
+ // exit immediately if no data
+ if (len <= 0) {
+ return 0;
+ }
+
+ // prepare temp buffer for calcing crc
+ uint8_t tmp_buff[len+3];
+ tmp_buff[0] = (uint8_t)get_address() << 1;
+ tmp_buff[1] = cmd;
+ tmp_buff[2] = tmp_buff[0] | (uint8_t)reading;
+ memcpy(&tmp_buff[3],buff,len);
+
+ // initialise crc to zero
+ uint8_t crc = 0;
+ uint8_t shift_reg = 0;
+ bool do_invert;
+
+ // for each byte in the stream
+ for (uint8_t i=0; i<sizeof(tmp_buff); i++) {
+ // load next data byte into the shift register
+ shift_reg = tmp_buff[i];
+ // for each bit in the current byte
+ for (uint8_t j=0; j<8; j++) {
+ do_invert = (crc ^ shift_reg) & 0x80;
+ crc <<= 1;
+ shift_reg <<= 1;
+ if (do_invert) {
+ crc ^= BATT_SMBUS_PEC_POLYNOMIAL;
+ }
+ }
+ }
+
+ // return result
+ return crc;
+}
+
+///////////////////////// shell functions ///////////////////////
+
+void
+batt_smbus_usage()
+{
+ warnx("missing command: try 'start', 'test', 'stop', 'search'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", BATT_SMBUS_I2C_BUS);
+ warnx(" -a addr (0x%x)", BATT_SMBUS_ADDR);
+}
+
+int
+batt_smbus_main(int argc, char *argv[])
+{
+ int i2cdevice = BATT_SMBUS_I2C_BUS;
+ int batt_smbusadr = BATT_SMBUS_ADDR; /* 7bit */
+
+ int ch;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ batt_smbusadr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ batt_smbus_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ batt_smbus_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ if (!strcmp(verb, "start")) {
+ if (g_batt_smbus != nullptr) {
+ errx(1, "already started");
+ } else {
+ // create new global object
+ g_batt_smbus = new BATT_SMBUS(i2cdevice, batt_smbusadr);
+
+ if (g_batt_smbus == nullptr) {
+ errx(1, "new failed");
+ }
+
+ if (OK != g_batt_smbus->init()) {
+ delete g_batt_smbus;
+ g_batt_smbus = nullptr;
+ errx(1, "init failed");
+ }
+ }
+
+ exit(0);
+ }
+
+ /* need the driver past this point */
+ if (g_batt_smbus == nullptr) {
+ warnx("not started");
+ batt_smbus_usage();
+ exit(1);
+ }
+
+ if (!strcmp(verb, "test")) {
+ g_batt_smbus->test();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "stop")) {
+ delete g_batt_smbus;
+ g_batt_smbus = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(verb, "search")) {
+ g_batt_smbus->search();
+ exit(0);
+ }
+
+ batt_smbus_usage();
+ exit(0);
+}
diff --git a/src/drivers/batt_smbus/module.mk b/src/drivers/batt_smbus/module.mk
new file mode 100644
index 000000000..b32ea6e55
--- /dev/null
+++ b/src/drivers/batt_smbus/module.mk
@@ -0,0 +1,8 @@
+#
+# driver for SMBus smart batteries
+#
+
+MODULE_COMMAND = batt_smbus
+SRCS = batt_smbus.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 705b398b0..206e71ddc 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -58,7 +58,7 @@ public:
/**
* Get the address
*/
- int16_t get_address() { return _address; }
+ int16_t get_address() const { return _address; }
protected:
/**
diff --git a/src/drivers/drv_batt_smbus.h b/src/drivers/drv_batt_smbus.h
new file mode 100644
index 000000000..ca130c84e
--- /dev/null
+++ b/src/drivers/drv_batt_smbus.h
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_batt_smbus.h
+ *
+ * SMBus battery monitor device API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+#include "drv_orb_dev.h"
+
+/* device path */
+#define BATT_SMBUS_DEVICE_PATH "/dev/batt_smbus"
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index 682cbf241..036798543 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -75,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
@@ -204,7 +205,7 @@ private:
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
PX4FLOW::PX4FLOW(int bus, int address, enum Rotation rotation) :
- I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000), //400khz
+ I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, PX4FLOW_I2C_MAX_BUS_SPEED), /* 100-400 KHz */
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index dac2ce59a..0e2a5356b 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -52,5 +52,5 @@ MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
-EXTRACXXFLAGS = -Wframe-larger-than=1900
+EXTRACXXFLAGS = -Wframe-larger-than=2000
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..45dcddb9c 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -400,7 +400,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
/* fetch initial parameter values */
parameters_update();
- // set correct uORB ID, depending on if vehicle is VTOL or not
+
+ /* 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);
@@ -724,22 +725,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 +756,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 +827,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 +853,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 +888,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 +989,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);
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/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 1f40e634e..5f8f8d02f 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -50,7 +50,8 @@
* Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).
*
* @unit meters
- * @min 0.0
+ * @min 20
+ * @max 200
* @group Mission
*/
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
@@ -61,10 +62,11 @@ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
* Default acceptance radius, overridden by acceptance radius of waypoint if set.
*
* @unit meters
- * @min 1.0
+ * @min 0.05
+ * @max 200
* @group Mission
*/
-PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
+PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 10.0f);
/**
* Set OBC mode for data link loss
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
index bfe6ce7e1..1568233b0 100644
--- a/src/modules/navigator/rtl_params.c
+++ b/src/modules/navigator/rtl_params.c
@@ -53,7 +53,8 @@
* Default value of loiter radius after RTL (fixedwing only).
*
* @unit meters
- * @min 0.0
+ * @min 20
+ * @max 200
* @group RTL
*/
PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
@@ -65,10 +66,10 @@ PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
*
* @unit meters
* @min 0
- * @max 1
+ * @max 150
* @group RTL
*/
-PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
+PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 60);
/**
@@ -78,7 +79,7 @@ PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
* Land (i.e. slowly descend) from this altitude if autolanding allowed.
*
* @unit meters
- * @min 0
+ * @min 2
* @max 100
* @group RTL
*/
@@ -92,7 +93,7 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 20);
*
* @unit seconds
* @min -1
- * @max
+ * @max 300
* @group RTL
*/
PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index b78b430aa..5b047f538 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -468,7 +468,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
- LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
+ LOG_FORMAT(FLOW, "QBffffffLLHhB", "IntT,ID,RawX,RawY,RX,RY,RZ,Dist,TSpan,DtSonar,FrmCnt,GT,Qlty"),
LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
LOG_FORMAT(ESC, "HBBBHHffiffH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),