aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
m---------mavlink/include/mavlink/v1.00
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig2
-rw-r--r--src/drivers/device/device.cpp1
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp6
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp5
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp15
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp4
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/px4iofirmware/controls.c4
-rw-r--r--src/systemcmds/mtd/24xxxx_mtd.c15
m---------uavcan0
11 files changed, 35 insertions, 19 deletions
diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0
-Subproject 2423e47b4f9169e77f7194b36fa2118e018c94e
+Subproject 8587a007cf89cb13f146ac46be94b61276343ce
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index cd9c05b13..edf49b26e 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -287,7 +287,7 @@ CONFIG_STM32_USART_SINGLEWIRE=y
#
# CONFIG_STM32_I2C_DYNTIMEO is not set
CONFIG_STM32_I2CTIMEOSEC=0
-CONFIG_STM32_I2CTIMEOMS=1
+CONFIG_STM32_I2CTIMEOMS=10
# CONFIG_STM32_I2C_DUTY16_9 is not set
#
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index f1f777dce..d46901683 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -97,6 +97,7 @@ Device::Device(const char *name,
/* setup a default device ID. When bus_type is UNKNOWN the
other fields are invalid */
+ _device_id.devid = 0;
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
_device_id.devid_s.bus = 0;
_device_id.devid_s.address = 0;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 6880cf0f8..01c89192a 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1519,8 +1519,10 @@ LSM303D::measure()
{
// if the accel doesn't have any data ready then re-schedule
// for 100 microseconds later. This ensures we don't double
- // read a value and then miss the next value
- if (stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
+ // 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;
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 2c50e5c75..a61346c2e 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -382,6 +382,7 @@ FixedwingEstimator::FixedwingEstimator() :
_local_pos({}),
_gps({}),
_wind({}),
+ _distance{},
_gyro_offsets({}),
_accel_offsets({}),
@@ -782,7 +783,7 @@ FixedwingEstimator::task_main()
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
@@ -1084,7 +1085,7 @@ FixedwingEstimator::task_main()
float baro_elapsed = (_baro.timestamp - baro_last) / 1e6f;
- _ekf->updateDtHgtFilt(math::constrain(baro_elapsed, 0.001f, 0.1));
+ _ekf->updateDtHgtFilt(math::constrain(baro_elapsed, 0.001f, 0.1f));
_ekf->baroHgt = _baro.altitude;
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index 94a6d165f..c17e034ad 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -119,6 +119,7 @@ AttPosEKF::AttPosEKF() :
inhibitWindStates(true),
inhibitMagStates(true),
inhibitGndState(true),
+ inhibitScaleState(true),
onGround(true),
staticMode(true),
@@ -2560,15 +2561,15 @@ void AttPosEKF::CovarianceInit()
P[22][22] = sq(0.5f);
}
-float AttPosEKF::ConstrainFloat(float val, float min, float max)
+float AttPosEKF::ConstrainFloat(float val, float min_val, float max_val)
{
float ret;
- if (val > max) {
- ret = max;
- ekf_debug("> max: %8.4f, val: %8.4f", (double)max, (double)val);
- } else if (val < min) {
- ret = min;
- ekf_debug("< min: %8.4f, val: %8.4f", (double)min, (double)val);
+ if (val > max_val) {
+ ret = max_val;
+ ekf_debug("> max: %8.4f, val: %8.4f", (double)max_val, (double)val);
+ } else if (val < min_val) {
+ ret = min_val;
+ ekf_debug("< min: %8.4f, val: %8.4f", (double)min_val, (double)val);
} else {
ret = val;
}
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index a2f3828ff..c182cfdb9 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -162,6 +162,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
break;
case NAVIGATION_STATE_AUTO_RTL:
+ /* fallthrough */
+ case NAVIGATION_STATE_AUTO_RCRECOVER:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -170,6 +172,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
break;
case NAVIGATION_STATE_LAND:
+ case NAVIGATION_STATE_AUTO_LANDENGFAIL:
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
/* fallthrough */
case NAVIGATION_STATE_DESCEND:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 72dc2815c..c44d4c35e 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -61,6 +61,4 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
-EXTRACXXFLAGS = -Weffc++
-
MAXOPTIMIZATION = -Os
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 622f20c7d..7b127759a 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -52,7 +52,7 @@
#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
-static bool dsm_port_input(uint8_t *rssi, bool *dsm_updated, bool *st24_updated);
+static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated);
static perf_counter_t c_gather_dsm;
static perf_counter_t c_gather_sbus;
@@ -60,7 +60,7 @@ static perf_counter_t c_gather_ppm;
static int _dsm_fd;
-bool dsm_port_input(uint8_t *rssi, bool *dsm_updated, bool *st24_updated)
+bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated)
{
perf_begin(c_gather_dsm);
uint16_t temp_count = r_raw_rc_count;
diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c
index 991363797..f85ed8e2d 100644
--- a/src/systemcmds/mtd/24xxxx_mtd.c
+++ b/src/systemcmds/mtd/24xxxx_mtd.c
@@ -80,11 +80,17 @@
/* As a minimum, the size of the AT24 part and its 7-bit I2C address are required. */
#ifndef CONFIG_AT24XX_SIZE
-# warning "Assuming AT24 size 64"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 size 64"
+ */
# define CONFIG_AT24XX_SIZE 64
#endif
#ifndef CONFIG_AT24XX_ADDR
-# warning "Assuming AT24 address of 0x50"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 address of 0x50"
+ */
# define CONFIG_AT24XX_ADDR 0x50
#endif
@@ -115,7 +121,10 @@
*/
#ifndef CONFIG_AT24XX_MTD_BLOCKSIZE
-# warning "Assuming driver block size is the same as the FLASH page size"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming driver block size is the same as the FLASH page size"
+ */
# define CONFIG_AT24XX_MTD_BLOCKSIZE AT24XX_PAGESIZE
#endif
diff --git a/uavcan b/uavcan
-Subproject 286adbcc56c4b093143b647ec7546abb149cd53
+Subproject 01d5bb242a6197e17e0ed466ed86e7ba42bd7d0