aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-04-29 15:42:07 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-04-29 15:42:07 +0200
commit775499321adc0b69d2845ffd24cb00a070ae09a0 (patch)
treec699874af412c64f615c9818d2b5ecd2eb520f74
parent606f3cba5c932d6aba0e383e915b02b78009fd9f (diff)
parent2ee02e5e4b455ef8ce136d62f2985b84357ef19f (diff)
downloadpx4-firmware-775499321adc0b69d2845ffd24cb00a070ae09a0.tar.gz
px4-firmware-775499321adc0b69d2845ffd24cb00a070ae09a0.tar.bz2
px4-firmware-775499321adc0b69d2845ffd24cb00a070ae09a0.zip
Merge remote-tracking branch 'upstream/master' into geo
-rw-r--r--Debug/NuttX10
-rw-r--r--Debug/Nuttx.py16
-rw-r--r--Documentation/rc_mode_switch.odgbin22232 -> 22421 bytes
-rw-r--r--Documentation/rc_mode_switch.pdfbin28728 -> 29666 bytes
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS16
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk11
-rw-r--r--src/drivers/airspeed/airspeed.cpp44
-rw-r--r--src/drivers/airspeed/airspeed.h7
-rw-r--r--src/drivers/drv_pwm_output.h3
-rw-r--r--src/drivers/drv_tone_alarm.h1
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp14
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp4
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp13
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp1
-rw-r--r--src/drivers/px4io/px4io.cpp21
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp2
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.cpp11
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.h6
-rw-r--r--src/lib/launchdetection/LaunchDetector.cpp7
-rw-r--r--src/lib/launchdetection/LaunchDetector.h6
-rw-r--r--src/lib/launchdetection/LaunchMethod.h6
-rw-r--r--src/lib/launchdetection/launchdetection_params.c5
-rw-r--r--src/lib/launchdetection/module.mk2
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c2
-rw-r--r--src/modules/commander/commander.cpp125
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp3
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp357
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h2
-rw-r--r--src/modules/commander/state_machine_helper.cpp185
-rw-r--r--src/modules/commander/state_machine_helper.h2
-rw-r--r--src/modules/dataman/dataman.c33
-rw-r--r--src/modules/dataman/dataman.h5
-rw-r--r--src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp6
-rw-r--r--src/modules/mavlink/mavlink.c6
-rw-r--r--src/modules/mavlink/mavlink_main.cpp8
-rw-r--r--src/modules/mavlink/mavlink_main.h3
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp22
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp34
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_params.c28
-rw-r--r--src/modules/px4iofirmware/protocol.h4
-rw-r--r--src/modules/px4iofirmware/registers.c6
-rw-r--r--src/modules/sensors/sensors.cpp34
-rw-r--r--src/modules/systemlib/system_params.c27
-rw-r--r--src/modules/uORB/topics/vehicle_status.h2
-rw-r--r--src/modules/unit_test/unit_test.cpp27
-rw-r--r--src/modules/unit_test/unit_test.h69
-rw-r--r--src/systemcmds/config/config.c2
48 files changed, 732 insertions, 468 deletions
diff --git a/Debug/NuttX b/Debug/NuttX
index 3b95e96b2..d34e9f5b4 100644
--- a/Debug/NuttX
+++ b/Debug/NuttX
@@ -34,10 +34,10 @@ define _showheap
else
set $MM_ALLOC_BIT = 0x80000000
end
- printf "HEAP %d %p - %p\n", $index, g_heapstart[$index], g_heapend[$index]
+ printf "HEAP %d %p - %p\n", $index, g_mmheap.mm_heapstart[$index], g_mmheap.mm_heapend[$index]
printf "ptr size\n"
- set $node = (char *)g_heapstart[$index] + sizeof(struct mm_allocnode_s)
- while $node < g_heapend[$index]
+ set $node = (char *)g_mmheap.mm_heapstart[$index] + sizeof(struct mm_allocnode_s)
+ while $node < g_mmheap.mm_heapend[$index]
printf " %p", $node
set $nodestruct = (struct mm_allocnode_s *)$node
printf " %u", $nodestruct->size
@@ -47,7 +47,7 @@ define _showheap
else
set $used = $used + $nodestruct->size
end
- if ($nodestruct->size > g_heapsize) || (($node + $nodestruct->size) > g_heapend[$index])
+ if ($nodestruct->size > g_mmheap.mm_heapsize) || (($node + $nodestruct->size) > g_mmheap.mm_heapend[$index])
printf " (BAD SIZE)"
end
printf "\n"
@@ -59,7 +59,7 @@ define _showheap
end
define showheap
- set $nheaps = sizeof(g_heapstart) / sizeof(g_heapstart[0])
+ set $nheaps = sizeof(g_mmheap.mm_heapstart) / sizeof(g_mmheap.mm_heapstart[0])
printf "Printing %d heaps\n", $nheaps
set $heapindex = (int)0
while $heapindex < $nheaps
diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py
index 093edd0e0..7cc21b99f 100644
--- a/Debug/Nuttx.py
+++ b/Debug/Nuttx.py
@@ -306,12 +306,15 @@ class NX_show_heap (gdb.Command):
def __init__(self):
super(NX_show_heap, self).__init__('show heap', gdb.COMMAND_USER)
- if gdb.lookup_type('struct mm_allocnode_s').sizeof == 8:
- self._allocflag = 0x80000000
- self._allocnodesize = 8
- else:
+ struct_mm_allocnode_s = gdb.lookup_type('struct mm_allocnode_s')
+ preceding_size = struct_mm_allocnode_s['preceding'].type.sizeof
+ if preceding_size == 2:
self._allocflag = 0x8000
- self._allocnodesize = 4
+ elif preceding_size == 4:
+ self._allocflag = 0x80000000
+ else:
+ raise gdb.GdbError('invalid mm_allocnode_s.preceding size %u' % preceding_size)
+ self._allocnodesize = struct_mm_allocnode_s.sizeof
def _node_allocated(self, allocnode):
if allocnode['preceding'] & self._allocflag:
@@ -333,7 +336,8 @@ class NX_show_heap (gdb.Command):
state = ''
else:
state = '(free)'
- print ' {} {} {}'.format(allocnode.address + 8, self._node_size(allocnode), state)
+ print ' {} {} {}'.format(allocnode.address + self._allocnodesize,
+ self._node_size(allocnode), state)
cursor += self._node_size(allocnode) / self._allocnodesize
def invoke(self, args, from_tty):
diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg
index 29d738c39..1ef05458f 100644
--- a/Documentation/rc_mode_switch.odg
+++ b/Documentation/rc_mode_switch.odg
Binary files differ
diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf
index 856dd55c5..b1a468d17 100644
--- a/Documentation/rc_mode_switch.pdf
+++ b/Documentation/rc_mode_switch.pdf
Binary files differ
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index ea5cf8deb..492afcb4c 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -120,6 +120,8 @@ then
set EXIT_ON_END no
set MAV_TYPE none
set LOAD_DEFAULT_APPS yes
+ set GPS yes
+ set GPS_FAKE no
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -437,9 +439,19 @@ then
echo "[init] Start logging"
sh /etc/init.d/rc.logging
fi
-
- gps start
+ if [ $GPS == yes ]
+ then
+ echo "[init] Start GPS"
+ if [ $GPS_FAKE == yes ]
+ then
+ echo "[init] Faking GPS"
+ gps start -f
+ else
+ gps start
+ fi
+ fi
+
#
# Start up ARDrone Motor interface
#
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index bb729e103..b519e0e7a 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -1,5 +1,5 @@
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -125,7 +125,11 @@ ARCHWARNINGS = -Wall \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
- -Wno-unused-parameter
+ -Wno-unused-parameter \
+ -Werror=format-security \
+ -Werror=array-bounds \
+ -Wfatal-errors \
+ -Wformat=1
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
@@ -142,7 +146,8 @@ ARCHCWARNINGS = $(ARCHWARNINGS) \
# C++-specific warnings
#
-ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-missing-field-initializers
# pull in *just* libm from the toolchain ... this is grody
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 524151c90..41942aacd 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -82,10 +82,12 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const cha
_buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
_max_differential_pressure_pa(0),
_sensor_ok(false),
+ _last_published_sensor_ok(true), /* initialize differently to force publication */
_measure_ticks(0),
_collect_phase(false),
_diff_pres_offset(0.0f),
_airspeed_pub(-1),
+ _subsys_pub(-1),
_class_instance(-1),
_conversion_interval(conversion_interval),
_sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
@@ -149,8 +151,7 @@ Airspeed::init()
}
ret = OK;
- /* sensor is ok, but we don't really know if it is within range */
- _sensor_ok = true;
+
out:
return ret;
}
@@ -344,22 +345,6 @@ Airspeed::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1);
-
- /* notify about state change */
- struct subsystem_info_s info = {
- true,
- true,
- true,
- SUBSYSTEM_TYPE_DIFFPRESSURE
- };
- static orb_advert_t pub = -1;
-
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
-
- } else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
- }
}
void
@@ -369,11 +354,34 @@ Airspeed::stop()
}
void
+Airspeed::update_status()
+{
+ if (_sensor_ok != _last_published_sensor_ok) {
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ _sensor_ok,
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
+
+ if (_subsys_pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), _subsys_pub, &info);
+ } else {
+ _subsys_pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+
+ _last_published_sensor_ok = _sensor_ok;
+ }
+}
+
+void
Airspeed::cycle_trampoline(void *arg)
{
Airspeed *dev = (Airspeed *)arg;
dev->cycle();
+ dev->update_status();
}
void
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index 186602eda..0b8e949c9 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -118,14 +118,21 @@ protected:
virtual int measure() = 0;
virtual int collect() = 0;
+ /**
+ * Update the subsystem status
+ */
+ void update_status();
+
work_s _work;
float _max_differential_pressure_pa;
bool _sensor_ok;
+ bool _last_published_sensor_ok;
int _measure_ticks;
bool _collect_phase;
float _diff_pres_offset;
orb_advert_t _airspeed_pub;
+ orb_advert_t _subsys_pub;
int _class_instance;
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 7a93e513e..972573f9f 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -199,6 +199,9 @@ ORB_DECLARE(output_pwm);
/** get the lockdown override flag to enable outputs in HIL */
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
+/** force safety switch off (to disable use of safety switch) */
+#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
+
/*
*
*
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index 147d7123a..b7981e9c4 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -148,6 +148,7 @@ enum {
TONE_BATTERY_WARNING_FAST_TUNE,
TONE_GPS_WARNING_TUNE,
TONE_ARMING_FAILURE_TUNE,
+ TONE_PARACHUTE_RELEASE_TUNE,
TONE_NUMBER_OF_TUNES
};
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index d873a1132..146a06e7c 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -207,14 +207,18 @@ ETSAirspeed::collect()
void
ETSAirspeed::cycle()
{
+ int ret;
+
/* collection phase? */
if (_collect_phase) {
/* perform collection */
- if (OK != collect()) {
+ ret = collect();
+ if (OK != ret) {
perf_count(_comms_errors);
/* restart the measurement state machine */
start();
+ _sensor_ok = false;
return;
}
@@ -238,8 +242,12 @@ ETSAirspeed::cycle()
}
/* measurement phase */
- if (OK != measure())
- log("measure error");
+ ret = measure();
+ if (OK != ret) {
+ debug("measure error");
+ }
+
+ _sensor_ok = (ret == OK);
/* next phase is collection */
_collect_phase = true;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index cb97354ec..cdc9d3106 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -715,7 +715,7 @@ HMC5883::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ debug("collection error");
/* restart the measurement state machine */
start();
return;
@@ -742,7 +742,7 @@ HMC5883::cycle()
/* measurement phase */
if (OK != measure())
- log("measure error");
+ debug("measure error");
/* next phase is collection */
_collect_phase = true;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 1ad383ee0..c0f3c28e0 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -288,13 +288,17 @@ MEASAirspeed::collect()
void
MEASAirspeed::cycle()
{
+ int ret;
+
/* collection phase? */
if (_collect_phase) {
/* perform collection */
- if (OK != collect()) {
+ ret = collect();
+ if (OK != ret) {
/* restart the measurement state machine */
start();
+ _sensor_ok = false;
return;
}
@@ -318,10 +322,13 @@ MEASAirspeed::cycle()
}
/* measurement phase */
- if (OK != measure()) {
- log("measure error");
+ ret = measure();
+ if (OK != ret) {
+ debug("measure error");
}
+ _sensor_ok = (ret == OK);
+
/* next phase is collection */
_collect_phase = true;
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 705e98eea..3cb9abc49 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -1015,7 +1015,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1):
/* copy the current output value from the channel */
- *(servo_position_t *)arg = Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue;
+ *(servo_position_t *)arg = Motor[cmd - PWM_SERVO_GET(0)].RawPwmValue;
break;
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index a70ff6c5c..7258d5f9e 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -736,6 +736,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
+ case PWM_SERVO_SET_FORCE_SAFETY_OFF:
// these are no-ops, as no safety switch
break;
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index e318e206a..8458c2fdb 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -91,6 +91,8 @@
#include "uploader.h"
+#include "modules/dataman/dataman.h"
+
extern device::Device *PX4IO_i2c_interface() weak_function;
extern device::Device *PX4IO_serial_interface() weak_function;
@@ -568,9 +570,15 @@ int
PX4IO::init()
{
int ret;
+ param_t sys_restart_param;
+ int sys_restart_val = DM_INIT_REASON_VOLATILE;
ASSERT(_task == -1);
+ sys_restart_param = param_find("SYS_RESTART_TYPE");
+ /* Indicate restart type is unknown */
+ param_set(sys_restart_param, &sys_restart_val);
+
/* do regular cdev init */
ret = CDev::init();
@@ -720,6 +728,11 @@ PX4IO::init()
/* keep waiting for state change for 2 s */
} while (!safety.armed);
+ /* Indicate restart type is in-flight */
+ sys_restart_val = DM_INIT_REASON_IN_FLIGHT;
+ param_set(sys_restart_param, &sys_restart_val);
+
+
/* regular boot, no in-air restart, init IO */
} else {
@@ -745,6 +758,10 @@ PX4IO::init()
}
}
+ /* Indicate restart type is power on */
+ sys_restart_val = DM_INIT_REASON_POWER_ON;
+ param_set(sys_restart_param, &sys_restart_val);
+
}
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
@@ -2129,6 +2146,10 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
case PWM_SERVO_GET_DISABLE_LOCKDOWN:
*(unsigned *)arg = _lockdown_override;
+
+ case PWM_SERVO_SET_FORCE_SAFETY_OFF:
+ /* force safety swith off */
+ ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
break;
case DSM_BIND_START:
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 8ed0de58c..810f4aacc 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -335,6 +335,7 @@ ToneAlarm::ToneAlarm() :
_default_tunes[TONE_BATTERY_WARNING_FAST_TUNE] = "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8"; //battery warning fast
_default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow
_default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<<BAP";
+ _default_tunes[TONE_PARACHUTE_RELEASE_TUNE] = "MFT255L16agagagag"; // parachute release
_tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
_tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
@@ -346,6 +347,7 @@ ToneAlarm::ToneAlarm() :
_tune_names[TONE_BATTERY_WARNING_FAST_TUNE] = "fast_bat"; // battery warning fast
_tune_names[TONE_GPS_WARNING_TUNE] = "gps_warning"; // gps warning
_tune_names[TONE_ARMING_FAILURE_TUNE] = "arming_failure"; //fail to arm
+ _tune_names[TONE_PARACHUTE_RELEASE_TUNE] = "parachute_release"; // parachute release
}
ToneAlarm::~ToneAlarm()
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp
index 12f80c4a3..c555a0a69 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.cpp
+++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -10,9 +10,9 @@
* 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 documentation4 and/or other materials provided with the
+ * the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name ECL nor the names of its contributors may be
+ * 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.
*
@@ -33,9 +33,10 @@
/**
* @file CatapultLaunchMethod.cpp
- * Catpult Launch detection
+ * Catapult Launch detection
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
- * Authors and acknowledgements in header.
*/
#include "CatapultLaunchMethod.h"
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h
index 55c46ff3f..23757f6f3 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.h
+++ b/src/lib/launchdetection/CatapultLaunchMethod.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -10,9 +10,9 @@
* 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 documentation4 and/or other materials provided with the
+ * the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name ECL nor the names of its contributors may be
+ * 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.
*
diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp
index bf539701b..3bf47bbb0 100644
--- a/src/lib/launchdetection/LaunchDetector.cpp
+++ b/src/lib/launchdetection/LaunchDetector.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -12,7 +12,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name ECL nor the names of its contributors may be
+ * 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.
*
@@ -30,12 +30,11 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
-
/**
* @file launchDetection.cpp
* Auto Detection for different launch methods (e.g. catapult)
*
- * Authors and acknowledgements in header.
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "LaunchDetector.h"
diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h
index 8066ebab3..1a214b66e 100644
--- a/src/lib/launchdetection/LaunchDetector.h
+++ b/src/lib/launchdetection/LaunchDetector.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -10,9 +10,9 @@
* 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 documentation4 and/or other materials provided with the
+ * the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name ECL nor the names of its contributors may be
+ * 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.
*
diff --git a/src/lib/launchdetection/LaunchMethod.h b/src/lib/launchdetection/LaunchMethod.h
index 01fa7050e..e04467f6a 100644
--- a/src/lib/launchdetection/LaunchMethod.h
+++ b/src/lib/launchdetection/LaunchMethod.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -10,9 +10,9 @@
* 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 documentation4 and/or other materials provided with the
+ * the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name ECL nor the names of its contributors may be
+ * 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.
*
diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c
index 45d7957f1..8df8c696c 100644
--- a/src/lib/launchdetection/launchdetection_params.c
+++ b/src/lib/launchdetection/launchdetection_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -18,7 +17,7 @@
* 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
+ * "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,
diff --git a/src/lib/launchdetection/module.mk b/src/lib/launchdetection/module.mk
index 13648b74c..de0174e37 100644
--- a/src/lib/launchdetection/module.mk
+++ b/src/lib/launchdetection/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2013 Estimation and Control Library (ECL). All rights reserved.
+# Copyright (c) 2012, 2013, 2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
index 4154e3db4..3ff3d9922 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
@@ -40,6 +40,7 @@
*/
#include "attitude_estimator_ekf_params.h"
+#include <math.h>
/* Extended Kalman Filter covariances */
@@ -113,6 +114,7 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
param_get(h->yaw_off, &(p->yaw_off));
param_get(h->mag_decl, &(p->mag_decl));
+ p->mag_decl *= M_PI / 180.0f;
param_get(h->acc_comp, &(p->acc_comp));
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 23fe64769..2db30b066 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -117,7 +117,7 @@ extern struct system_load_s system_load;
#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-#define POSITION_TIMEOUT 30000 /**< consider the local or global position estimate invalid after 30ms */
+#define POSITION_TIMEOUT 100000 /**< consider the local or global position estimate invalid after 100ms */
#define RC_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
@@ -137,7 +137,7 @@ enum MAV_MODE_FLAG {
};
/* Mavlink file descriptors */
-static int mavlink_fd;
+static int mavlink_fd = 0;
/* flags */
static bool commander_initialized = false;
@@ -218,11 +218,10 @@ void print_reject_arm(const char *msg);
void print_status();
-int arm();
-int disarm();
-
transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy);
+
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
*/
@@ -289,12 +288,12 @@ int commander_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "arm")) {
- arm();
+ arm_disarm(true, mavlink_fd, "command line");
exit(0);
}
- if (!strcmp(argv[1], "disarm")) {
- disarm();
+ if (!strcmp(argv[1], "2")) {
+ arm_disarm(false, mavlink_fd, "command line");
exit(0);
}
@@ -364,30 +363,20 @@ void print_status()
static orb_advert_t status_pub;
-int arm()
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy)
{
- int arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
- return 0;
-
- } else {
- return 1;
- }
-}
-
-int disarm()
-{
- int arming_res = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
- return 0;
-
- } else {
- return 1;
- }
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
+ // output appropriate error messages if the state cannot transition.
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
+ if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
+ mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
+ } else if (arming_res == TRANSITION_DENIED) {
+ tune_negative(true);
+ }
+
+ return arming_res;
}
bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
@@ -430,37 +419,8 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
if (hil_ret == OK)
ret = true;
- // TODO remove debug code
- //mavlink_log_critical(mavlink_fd, "#audio: command setmode: %d %d", base_mode, custom_main_mode);
- /* set arming state */
- arming_res = TRANSITION_NOT_CHANGED;
-
- if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
- arming_res = TRANSITION_DENIED;
-
- } else {
- arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
- }
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by command");
- }
-
- } else {
- if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
- arming_state_t new_arming_state = (status->arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- arming_res = arming_state_transition(status, safety, new_arming_state, armed);
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] DISARMED by command");
- }
-
- } else {
- arming_res = TRANSITION_NOT_CHANGED;
- }
- }
+ // Transition the arming state
+ arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
if (arming_res == TRANSITION_CHANGED)
ret = true;
@@ -519,27 +479,19 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
- if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
- arming_res = TRANSITION_DENIED;
-
- } else {
- arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
- }
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#audio: ARMED by component arm cmd");
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- ret = true;
-
- } else {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- }
- }
+ // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
+ // We use an float epsilon delta to test float equality.
+ if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
+ mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
+ } else {
+ transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
+ if (arming_res == TRANSITION_DENIED) {
+ mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ } else {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ }
+ }
}
break;
@@ -1751,8 +1703,11 @@ set_control_mode()
control_mode.flag_control_auto_enabled = true;
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
- control_mode.flag_control_position_enabled = true;
- control_mode.flag_control_velocity_enabled = true;
+
+ /* in failsafe LAND mode position may be not available */
+ control_mode.flag_control_position_enabled = status.condition_local_position_valid;
+ control_mode.flag_control_velocity_enabled = status.condition_local_position_valid;
+
control_mode.flag_control_altitude_enabled = true;
control_mode.flag_control_climb_rate_enabled = true;
}
diff --git a/src/modules/commander/commander_tests/commander_tests.cpp b/src/modules/commander/commander_tests/commander_tests.cpp
index 6e72cf0d9..0abb84a82 100644
--- a/src/modules/commander/commander_tests/commander_tests.cpp
+++ b/src/modules/commander/commander_tests/commander_tests.cpp
@@ -48,8 +48,7 @@ extern "C" __EXPORT int commander_tests_main(int argc, char *argv[]);
int commander_tests_main(int argc, char *argv[])
{
- state_machine_helper_test();
- //state_machine_test();
+ stateMachineHelperTest();
return 0;
}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 40bedd9f3..8a946543d 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -49,13 +49,12 @@ public:
StateMachineHelperTest();
virtual ~StateMachineHelperTest();
- virtual const char* run_tests();
+ virtual void runTests(void);
private:
- const char* arming_state_transition_test();
- const char* arming_state_transition_arm_disarm_test();
- const char* main_state_transition_test();
- const char* is_safe_test();
+ bool armingStateTransitionTest();
+ bool mainStateTransitionTest();
+ bool isSafeTest();
};
StateMachineHelperTest::StateMachineHelperTest() {
@@ -64,61 +63,242 @@ StateMachineHelperTest::StateMachineHelperTest() {
StateMachineHelperTest::~StateMachineHelperTest() {
}
-const char*
-StateMachineHelperTest::arming_state_transition_test()
+bool StateMachineHelperTest::armingStateTransitionTest(void)
{
+ // These are the critical values from vehicle_status_s and actuator_armed_s which must be primed
+ // to simulate machine state prior to testing an arming state transition. This structure is also
+ // use to represent the expected machine state after the transition has been requested.
+ typedef struct {
+ arming_state_t arming_state; // vehicle_status_s.arming_state
+ bool armed; // actuator_armed_s.armed
+ bool ready_to_arm; // actuator_armed_s.ready_to_arm
+ } ArmingTransitionVolatileState_t;
+
+ // This structure represents a test case for arming_state_transition. It contains the machine
+ // state prior to transtion, the requested state to transition to and finally the expected
+ // machine state after transition.
+ typedef struct {
+ const char* assertMsg; // Text to show when test case fails
+ ArmingTransitionVolatileState_t current_state; // Machine state prior to transtion
+ hil_state_t hil_state; // Current vehicle_status_s.hil_state
+ bool condition_system_sensors_initialized; // Current vehicle_status_s.condition_system_sensors_initialized
+ bool safety_switch_available; // Current safety_s.safety_switch_available
+ bool safety_off; // Current safety_s.safety_off
+ arming_state_t requested_state; // Requested arming state to transition to
+ ArmingTransitionVolatileState_t expected_state; // Expected machine state after transition
+ transition_result_t expected_transition_result; // Expected result from arming_state_transition
+ } ArmingTransitionTest_t;
+
+ // We use these defines so that our test cases are more readable
+ #define ATT_ARMED true
+ #define ATT_DISARMED false
+ #define ATT_READY_TO_ARM true
+ #define ATT_NOT_READY_TO_ARM false
+ #define ATT_SENSORS_INITIALIZED true
+ #define ATT_SENSORS_NOT_INITIALIZED false
+ #define ATT_SAFETY_AVAILABLE true
+ #define ATT_SAFETY_NOT_AVAILABLE true
+ #define ATT_SAFETY_OFF true
+ #define ATT_SAFETY_ON false
+
+ // These are test cases for arming_state_transition
+ static const ArmingTransitionTest_t rgArmingTransitionTests[] = {
+ // TRANSITION_NOT_CHANGED tests
+
+ { "no transition: identical states",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_INIT,
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_NOT_CHANGED },
+
+ // TRANSITION_CHANGED tests
+
+ // Check all basic valid transitions, these don't require special state in vehicle_status_t or safety_s
+
+ { "transition: init to standby",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: init to standby error",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY_ERROR,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: init to reboot",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: standby to init",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_INIT,
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: standby to standby error",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY_ERROR,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: standby to reboot",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: armed to standby",
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: armed to armed error",
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED_ERROR,
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: armed error to standby error",
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY_ERROR,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: standby error to reboot",
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: in air restore to armed",
+ { ARMING_STATE_IN_AIR_RESTORE, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: in air restore to reboot",
+ { ARMING_STATE_IN_AIR_RESTORE, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ // hil on tests, standby error to standby not normally allowed
+
+ { "transition: standby error to standby, hil on",
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_ON, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ // Safety switch arming tests
+
+ { "transition: init to standby, no safety switch",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_NOT_AVAILABLE, ATT_SAFETY_OFF,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ { "transition: init to standby, safety switch off",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_OFF,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ // standby error
+ { "transition: armed error to standby error requested standby",
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_CHANGED },
+
+ // TRANSITION_DENIED tests
+
+ // Check some important basic invalid transitions, these don't require special state in vehicle_status_t or safety_s
+
+ { "no transition: init to armed",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: standby to armed error",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED_ERROR,
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: armed to init",
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_INIT,
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: armed to reboot",
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: armed error to armed",
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: armed error to reboot",
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_REBOOT,
+ { ARMING_STATE_ARMED_ERROR, ATT_ARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: standby error to armed",
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: standby error to standby",
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_STANDBY_ERROR, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: reboot to armed",
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_REBOOT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ { "no transition: in air restore to standby",
+ { ARMING_STATE_IN_AIR_RESTORE, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_IN_AIR_RESTORE, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ // Sensor tests
+
+ { "no transition: init to standby - sensors not initialized",
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_NOT_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_STANDBY,
+ { ARMING_STATE_INIT, ATT_DISARMED, ATT_NOT_READY_TO_ARM }, TRANSITION_DENIED },
+
+ // Safety switch arming tests
+
+ { "no transition: init to standby, safety switch on",
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_ON,
+ ARMING_STATE_ARMED,
+ { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, TRANSITION_DENIED },
+ };
+
struct vehicle_status_s status;
- struct safety_s safety;
- arming_state_t new_arming_state;
- struct actuator_armed_s armed;
-
- // Identical states.
- status.arming_state = ARMING_STATE_INIT;
- new_arming_state = ARMING_STATE_INIT;
- mu_assert("no transition: identical states",
- TRANSITION_NOT_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed));
-
- // INIT to STANDBY.
- armed.armed = false;
- armed.ready_to_arm = false;
- status.arming_state = ARMING_STATE_INIT;
- status.condition_system_sensors_initialized = true;
- new_arming_state = ARMING_STATE_STANDBY;
- mu_assert("transition: init to standby",
- TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed));
- mu_assert("current state: standby", ARMING_STATE_STANDBY == status.arming_state);
- mu_assert("not armed", !armed.armed);
- mu_assert("ready to arm", armed.ready_to_arm);
-
- // INIT to STANDBY, sensors not initialized.
- armed.armed = false;
- armed.ready_to_arm = false;
- status.arming_state = ARMING_STATE_INIT;
- status.condition_system_sensors_initialized = false;
- new_arming_state = ARMING_STATE_STANDBY;
- mu_assert("no transition: sensors not initialized",
- TRANSITION_DENIED == arming_state_transition(&status, &safety, new_arming_state, &armed));
- mu_assert("current state: init", ARMING_STATE_INIT == status.arming_state);
- mu_assert("not armed", !armed.armed);
- mu_assert("not ready to arm", !armed.ready_to_arm);
-
- return 0;
-}
-
-const char*
-StateMachineHelperTest::arming_state_transition_arm_disarm_test()
-{
- struct vehicle_status_s status;
- struct safety_s safety;
- arming_state_t new_arming_state;
+ struct safety_s safety;
struct actuator_armed_s armed;
-
- // TODO(sjwilks): ARM then DISARM.
- return 0;
+
+ size_t cArmingTransitionTests = sizeof(rgArmingTransitionTests) / sizeof(rgArmingTransitionTests[0]);
+ for (size_t i=0; i<cArmingTransitionTests; i++) {
+ const ArmingTransitionTest_t* test = &rgArmingTransitionTests[i];
+
+ // Setup initial machine state
+ status.arming_state = test->current_state.arming_state;
+ status.condition_system_sensors_initialized = test->condition_system_sensors_initialized;
+ status.hil_state = test->hil_state;
+ safety.safety_switch_available = test->safety_switch_available;
+ safety.safety_off = test->safety_off;
+ armed.armed = test->current_state.armed;
+ armed.ready_to_arm = test->current_state.ready_to_arm;
+
+ // Attempt transition
+ transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed);
+
+ // Validate result of transition
+ ut_assert(test->assertMsg, test->expected_transition_result == result);
+ ut_assert(test->assertMsg, status.arming_state == test->expected_state.arming_state);
+ ut_assert(test->assertMsg, armed.armed == test->expected_state.armed);
+ ut_assert(test->assertMsg, armed.ready_to_arm == test->expected_state.ready_to_arm);
+ }
+
+ return true;
}
-const char*
-StateMachineHelperTest::main_state_transition_test()
+bool StateMachineHelperTest::mainStateTransitionTest(void)
{
struct vehicle_status_s current_state;
main_state_t new_main_state;
@@ -126,70 +306,69 @@ StateMachineHelperTest::main_state_transition_test()
// Identical states.
current_state.main_state = MAIN_STATE_MANUAL;
new_main_state = MAIN_STATE_MANUAL;
- mu_assert("no transition: identical states",
+ ut_assert("no transition: identical states",
TRANSITION_NOT_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
// AUTO to MANUAL.
current_state.main_state = MAIN_STATE_AUTO;
new_main_state = MAIN_STATE_MANUAL;
- mu_assert("transition changed: auto to manual",
+ ut_assert("transition changed: auto to manual",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
// MANUAL to SEATBELT.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
new_main_state = MAIN_STATE_SEATBELT;
- mu_assert("tranisition: manual to seatbelt",
+ ut_assert("tranisition: manual to seatbelt",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
+ ut_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
// MANUAL to SEATBELT, invalid local altitude.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = false;
new_main_state = MAIN_STATE_SEATBELT;
- mu_assert("no transition: invalid local altitude",
+ ut_assert("no transition: invalid local altitude",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
// MANUAL to EASY.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
new_main_state = MAIN_STATE_EASY;
- mu_assert("transition: manual to easy",
+ ut_assert("transition: manual to easy",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
+ ut_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
// MANUAL to EASY, invalid local position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = false;
new_main_state = MAIN_STATE_EASY;
- mu_assert("no transition: invalid position",
+ ut_assert("no transition: invalid position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
// MANUAL to AUTO.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_global_position_valid = true;
new_main_state = MAIN_STATE_AUTO;
- mu_assert("transition: manual to auto",
+ ut_assert("transition: manual to auto",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: auto", MAIN_STATE_AUTO == current_state.main_state);
+ ut_assert("current state: auto", MAIN_STATE_AUTO == current_state.main_state);
// MANUAL to AUTO, invalid global position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_global_position_valid = false;
new_main_state = MAIN_STATE_AUTO;
- mu_assert("no transition: invalid global position",
+ ut_assert("no transition: invalid global position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- return 0;
+ return true;
}
-const char*
-StateMachineHelperTest::is_safe_test()
+bool StateMachineHelperTest::isSafeTest(void)
{
struct vehicle_status_s current_state;
struct safety_s safety;
@@ -199,49 +378,45 @@ StateMachineHelperTest::is_safe_test()
armed.lockdown = false;
safety.safety_switch_available = true;
safety.safety_off = false;
- mu_assert("is safe: not armed", is_safe(&current_state, &safety, &armed));
+ ut_assert("is safe: not armed", is_safe(&current_state, &safety, &armed));
armed.armed = false;
armed.lockdown = true;
safety.safety_switch_available = true;
safety.safety_off = true;
- mu_assert("is safe: software lockdown", is_safe(&current_state, &safety, &armed));
+ ut_assert("is safe: software lockdown", is_safe(&current_state, &safety, &armed));
armed.armed = true;
armed.lockdown = false;
safety.safety_switch_available = true;
safety.safety_off = true;
- mu_assert("not safe: safety off", !is_safe(&current_state, &safety, &armed));
+ ut_assert("not safe: safety off", !is_safe(&current_state, &safety, &armed));
armed.armed = true;
armed.lockdown = false;
safety.safety_switch_available = true;
safety.safety_off = false;
- mu_assert("is safe: safety off", is_safe(&current_state, &safety, &armed));
+ ut_assert("is safe: safety off", is_safe(&current_state, &safety, &armed));
armed.armed = true;
armed.lockdown = false;
safety.safety_switch_available = false;
safety.safety_off = false;
- mu_assert("not safe: no safety switch", !is_safe(&current_state, &safety, &armed));
+ ut_assert("not safe: no safety switch", !is_safe(&current_state, &safety, &armed));
- return 0;
+ return true;
}
-const char*
-StateMachineHelperTest::run_tests()
+void StateMachineHelperTest::runTests(void)
{
- mu_run_test(arming_state_transition_test);
- mu_run_test(arming_state_transition_arm_disarm_test);
- mu_run_test(main_state_transition_test);
- mu_run_test(is_safe_test);
-
- return 0;
+ ut_run_test(armingStateTransitionTest);
+ ut_run_test(mainStateTransitionTest);
+ ut_run_test(isSafeTest);
}
-void
-state_machine_helper_test()
+void stateMachineHelperTest(void)
{
StateMachineHelperTest* test = new StateMachineHelperTest();
- test->UnitTest::print_results(test->run_tests());
+ test->runTests();
+ test->printResults();
}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.h b/src/modules/commander/commander_tests/state_machine_helper_test.h
index 10a68e602..bbf66255e 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.h
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.h
@@ -39,6 +39,6 @@
#ifndef STATE_MACHINE_HELPER_TEST_H_
#define STATE_MACHINE_HELPER_TEST_
-void state_machine_helper_test();
+void stateMachineHelperTest(void);
#endif /* STATE_MACHINE_HELPER_TEST_H_ */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index e6f245cf9..f09d586c7 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -69,10 +69,44 @@ static bool arming_state_changed = true;
static bool main_state_changed = true;
static bool failsafe_state_changed = true;
+// This array defines the arming state transitions. The rows are the new state, and the columns
+// are the current state. Using new state and current state you can index into the array which
+// will be true for a valid transition or false for a invalid transition. In some cases even
+// though the transition is marked as true additional checks must be made. See arming_state_transition
+// code for those checks.
+static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+};
+
+// You can index into the array with an arming_state_t in order to get it's textual representation
+static const char* state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
+};
+
transition_result_t
-arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety,
- arming_state_t new_arming_state, struct actuator_armed_s *armed)
+arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
+
/*
* Perform an atomic state update
*/
@@ -83,116 +117,63 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == status->arming_state) {
ret = TRANSITION_NOT_CHANGED;
-
} else {
-
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
-
} else {
armed->lockdown = false;
}
-
- switch (new_arming_state) {
- case ARMING_STATE_INIT:
-
- /* allow going back from INIT for calibration */
- if (status->arming_state == ARMING_STATE_STANDBY) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
- }
-
- break;
-
- case ARMING_STATE_STANDBY:
-
- /* allow coming from INIT and disarming from ARMED */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED
- || status->hil_state == HIL_STATE_ON) {
-
- /* sensors need to be initialized for STANDBY state */
- if (status->condition_system_sensors_initialized) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = true;
- }
- }
-
- break;
-
- case ARMING_STATE_ARMED:
-
- /* allow arming from STANDBY and IN-AIR-RESTORE */
- if ((status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
- && (!safety->safety_switch_available || safety->safety_off || status->hil_state == HIL_STATE_ON)) { /* only allow arming if safety is off */
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = true;
- }
-
- break;
-
- case ARMING_STATE_ARMED_ERROR:
-
- /* an armed error happens when ARMED obviously */
- if (status->arming_state == ARMING_STATE_ARMED) {
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = false;
- }
-
- break;
-
- case ARMING_STATE_STANDBY_ERROR:
-
- /* a disarmed error happens when in STANDBY or in INIT or after ARMED_ERROR */
- if (status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED_ERROR) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
- }
-
- break;
-
- case ARMING_STATE_REBOOT:
-
- /* an armed error happens when ARMED obviously */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
- }
-
- break;
-
- case ARMING_STATE_IN_AIR_RESTORE:
-
- /* XXX implement */
- break;
-
- default:
- break;
- }
-
- if (ret == TRANSITION_CHANGED) {
- status->arming_state = new_arming_state;
- arming_state_changed = true;
- }
- }
-
+
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ // Fail transition if we need safety switch press
+ // Allow if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first.");
+ }
+ valid_transition = false;
+ }
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
+ }
+ }
+
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
+
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
+ }
+
+ // Finish up the state transition
+ if (valid_transition) {
+ armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
+ armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
+ ret = TRANSITION_CHANGED;
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
/* end of atomic state update */
irqrestore(flags);
- if (ret == TRANSITION_DENIED)
- warnx("arming transition rejected");
+ if (ret == TRANSITION_DENIED) {
+ static const char* errMsg = "Invalid arming transition from %s to %s";
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index f04879ff9..0ddd4f05a 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -57,7 +57,7 @@ typedef enum {
} transition_result_t;
transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
- arming_state_t new_arming_state, struct actuator_armed_s *armed);
+ arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd = 0);
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index c132b0040..7505ba358 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -416,26 +416,26 @@ static int
_restart(dm_reset_reason reason)
{
unsigned char buffer[2];
- int offset, result = 0;
+ int offset = 0, result = 0;
/* We need to scan the entire file and invalidate and data that should not persist after the last reset */
/* Loop through all of the data segments and delete those that are not persistent */
- offset = 0;
-
while (1) {
size_t len;
/* Get data segment at current offset */
if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
- result = -1;
+ /* must be at eof */
break;
}
len = read(g_task_fd, buffer, sizeof(buffer));
- if (len == 0)
+ if (len != sizeof(buffer)) {
+ /* must be at eof */
break;
+ }
/* check if segment contains data */
if (buffer[0]) {
@@ -443,12 +443,12 @@ _restart(dm_reset_reason reason)
/* Whether data gets deleted depends on reset type and data segment's persistence setting */
if (reason == DM_INIT_REASON_POWER_ON) {
- if (buffer[1] != DM_PERSIST_POWER_ON_RESET) {
+ if (buffer[1] > DM_PERSIST_POWER_ON_RESET) {
clear_entry = 1;
}
} else {
- if ((buffer[1] != DM_PERSIST_POWER_ON_RESET) && (buffer[1] != DM_PERSIST_IN_FLIGHT_RESET)) {
+ if (buffer[1] > DM_PERSIST_IN_FLIGHT_RESET) {
clear_entry = 1;
}
}
@@ -628,6 +628,23 @@ task_main(int argc, char *argv[])
fsync(g_task_fd);
+ /* see if we need to erase any items based on restart type */
+ int sys_restart_val;
+ if (param_get(param_find("SYS_RESTART_TYPE"), &sys_restart_val) == OK) {
+ if (sys_restart_val == DM_INIT_REASON_POWER_ON) {
+ warnx("Power on restart");
+ _restart(DM_INIT_REASON_POWER_ON);
+ }
+ else if (sys_restart_val == DM_INIT_REASON_IN_FLIGHT) {
+ warnx("In flight restart");
+ _restart(DM_INIT_REASON_IN_FLIGHT);
+ }
+ else
+ warnx("Unknown restart");
+ }
+ else
+ warnx("Unknown restart");
+
/* We use two file descriptors, one for the caller context and one for the worker thread */
/* They are actually the same but we need to some way to reject caller request while the */
/* worker thread is shutting down but still processing requests */
@@ -724,7 +741,7 @@ start(void)
return -1;
}
- /* wait for the thread to actuall initialize */
+ /* wait for the thread to actually initialize */
sem_wait(&g_init_sema);
sem_destroy(&g_init_sema);
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index 33c9fcd15..4382baeb5 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -75,7 +75,8 @@ extern "C" {
/* The reason for the last reset */
typedef enum {
DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
- DM_INIT_REASON_IN_FLIGHT /* Data survives in-flight resets only */
+ DM_INIT_REASON_IN_FLIGHT, /* Data survives in-flight resets only */
+ DM_INIT_REASON_VOLATILE /* Data does not survive reset */
} dm_reset_reason;
/* Maximum size in bytes of a single item instance */
@@ -100,7 +101,7 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
- /* Retrieve from the data manager store */
+ /* Erase all items of this type */
__EXPORT int
dm_clear(
dm_item_t item /* The item type to clear */
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
index 79328d516..eaf518198 100644
--- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
@@ -732,21 +732,21 @@ FixedwingEstimator::task_main()
case 1:
{
const char* str = "NaN in states, resetting";
- warnx(str);
+ warnx("%s", str);
mavlink_log_critical(_mavlink_fd, str);
break;
}
case 2:
{
const char* str = "stale IMU data, resetting";
- warnx(str);
+ warnx("%s", str);
mavlink_log_critical(_mavlink_fd, str);
break;
}
case 3:
{
const char* str = "switching dynamic / static state";
- warnx(str);
+ warnx("%s", str);
mavlink_log_critical(_mavlink_fd, str);
break;
}
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index ad435b251..e49288a74 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -62,6 +62,12 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
+/**
+ * Use/Accept HIL GPS message (even if not in HIL mode)
+ * If set to 1 incomming HIL GPS messages are parsed.
+ * @group MAVLink
+ */
+PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
mavlink_system_t mavlink_system = {
100,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 227e99b48..7ecca0d65 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -208,6 +208,7 @@ Mavlink::Mavlink() :
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
+ _use_hil_gps(false),
_is_usb_uart(false),
_wait_to_transmit(false),
_received_messages(false),
@@ -487,11 +488,13 @@ void Mavlink::mavlink_update_system(void)
static param_t param_system_id;
static param_t param_component_id;
static param_t param_system_type;
+ static param_t param_use_hil_gps;
if (!initialized) {
param_system_id = param_find("MAV_SYS_ID");
param_component_id = param_find("MAV_COMP_ID");
param_system_type = param_find("MAV_TYPE");
+ param_use_hil_gps = param_find("MAV_USEHILGPS");
initialized = true;
}
@@ -516,6 +519,11 @@ void Mavlink::mavlink_update_system(void)
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
mavlink_system.type = system_type;
}
+
+ int32_t use_hil_gps;
+ param_get(param_use_hil_gps, &use_hil_gps);
+
+ _use_hil_gps = (bool)use_hil_gps;
}
int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 66d82b471..1bf51fd31 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -157,6 +157,8 @@ public:
bool get_hil_enabled() { return _hil_enabled; }
+ bool get_use_hil_gps() { return _use_hil_gps; }
+
bool get_flow_control_enabled() { return _flow_control_enabled; }
bool get_forwarding_on() { return _forwarding_on; }
@@ -223,6 +225,7 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
+ bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
bool _is_usb_uart; /**< Port is USB */
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
bool _received_messages; /**< Whether we've received valid mavlink messages. */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index db8f00e8f..ddbf4fc69 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -160,6 +160,9 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
* The HIL mode is enabled by the HIL bit flag
* in the system mode. Either send a set mode
* COMMAND_LONG message or a SET_MODE message
+ *
+ * Accept HIL GPS messages if use_hil_gps flag is true.
+ * This allows to provide fake gps measurements to the system.
*/
if (_mavlink->get_hil_enabled()) {
switch (msg->msgid) {
@@ -167,10 +170,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_hil_sensor(msg);
break;
- case MAVLINK_MSG_ID_HIL_GPS:
- handle_message_hil_gps(msg);
- break;
-
case MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
handle_message_hil_state_quaternion(msg);
break;
@@ -180,7 +179,20 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
}
}
- /* If we've received a valid message, mark the flag indicating so.
+
+ if (_mavlink->get_hil_enabled() || (_mavlink->get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) {
+ switch (msg->msgid) {
+ case MAVLINK_MSG_ID_HIL_GPS:
+ handle_message_hil_gps(msg);
+ break;
+
+ default:
+ break;
+ }
+
+ }
+
+ /* If we've received a valid message, mark the flag indicating so.
This is used in the '-w' command-line flag. */
_mavlink->set_has_received_messages(true);
}
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 6b797f222..7c625a0c5 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -148,17 +148,17 @@ private:
param_t xy_vel_d;
param_t xy_vel_max;
param_t xy_ff;
- param_t tilt_max;
+ param_t tilt_max_air;
param_t land_speed;
- param_t land_tilt_max;
+ param_t tilt_max_land;
} _params_handles; /**< handles for interesting parameters */
struct {
float thr_min;
float thr_max;
- float tilt_max;
+ float tilt_max_air;
float land_speed;
- float land_tilt_max;
+ float tilt_max_land;
math::Vector<3> pos_p;
math::Vector<3> vel_p;
@@ -308,9 +308,9 @@ MulticopterPositionControl::MulticopterPositionControl() :
_params_handles.xy_vel_d = param_find("MPC_XY_VEL_D");
_params_handles.xy_vel_max = param_find("MPC_XY_VEL_MAX");
_params_handles.xy_ff = param_find("MPC_XY_FF");
- _params_handles.tilt_max = param_find("MPC_TILT_MAX");
+ _params_handles.tilt_max_air = param_find("MPC_TILTMAX_AIR");
_params_handles.land_speed = param_find("MPC_LAND_SPEED");
- _params_handles.land_tilt_max = param_find("MPC_LAND_TILT");
+ _params_handles.tilt_max_land = param_find("MPC_TILTMAX_LND");
/* fetch initial parameter values */
parameters_update(true);
@@ -355,9 +355,11 @@ MulticopterPositionControl::parameters_update(bool force)
if (updated || force) {
param_get(_params_handles.thr_min, &_params.thr_min);
param_get(_params_handles.thr_max, &_params.thr_max);
- param_get(_params_handles.tilt_max, &_params.tilt_max);
+ param_get(_params_handles.tilt_max_air, &_params.tilt_max_air);
+ _params.tilt_max_air = math::radians(_params.tilt_max_air);
param_get(_params_handles.land_speed, &_params.land_speed);
- param_get(_params_handles.land_tilt_max, &_params.land_tilt_max);
+ param_get(_params_handles.tilt_max_land, &_params.tilt_max_land);
+ _params.tilt_max_land = math::radians(_params.tilt_max_land);
float v;
param_get(_params_handles.xy_p, &v);
@@ -839,13 +841,13 @@ MulticopterPositionControl::task_main()
thr_min = 0.0f;
}
- float tilt_max = _params.tilt_max;
+ float tilt_max = _params.tilt_max_air;
/* adjust limits for landing mode */
if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid &&
_pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
/* limit max tilt and min lift when landing */
- tilt_max = _params.land_tilt_max;
+ tilt_max = _params.tilt_max_land;
if (thr_min < 0.0f) {
thr_min = 0.0f;
@@ -1001,6 +1003,18 @@ MulticopterPositionControl::task_main()
_att_sp.roll_body = euler(0);
_att_sp.pitch_body = euler(1);
/* yaw already used to construct rot matrix, but actual rotation matrix can have different yaw near singularity */
+
+ } else if (!_control_mode.flag_control_manual_enabled) {
+ /* autonomous altitude control without position control (failsafe landing),
+ * force level attitude, don't change yaw */
+ R.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+
+ /* copy rotation matrix to attitude setpoint topic */
+ memcpy(&_att_sp.R_body[0][0], R.data, sizeof(_att_sp.R_body));
+ _att_sp.R_valid = true;
+
+ _att_sp.roll_body = 0.0f;
+ _att_sp.pitch_body = 0.0f;
}
_att_sp.thrust = thrust_abs;
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
index 0082a5e6a..104df4e59 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -100,6 +100,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
*
* Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY).
*
+ * @unit m/s
* @min 0.0
* @group Multicopter Position Control
*/
@@ -155,6 +156,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
*
* Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY).
*
+ * @unit m/s
* @min 0.0
* @group Multicopter Position Control
*/
@@ -172,31 +174,35 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
/**
- * Maximum tilt
+ * Maximum tilt angle in air
*
- * Limits maximum tilt in AUTO and EASY modes.
+ * Limits maximum tilt in AUTO and EASY modes during flight.
*
+ * @unit deg
* @min 0.0
- * @max 1.57
+ * @max 90.0
* @group Multicopter Position Control
*/
-PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_TILTMAX_AIR, 45.0f);
/**
- * Landing descend rate
+ * Maximum tilt during landing
+ *
+ * Limits maximum tilt angle on landing.
*
+ * @unit deg
* @min 0.0
+ * @max 90.0
* @group Multicopter Position Control
*/
-PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 1.0f);
+PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 15.0f);
/**
- * Maximum landing tilt
- *
- * Limits maximum tilt on landing.
+ * Landing descend rate
*
+ * @unit m/s
* @min 0.0
- * @max 1.57
* @group Multicopter Position Control
*/
-PARAM_DEFINE_FLOAT(MPC_LAND_TILT, 0.3f);
+PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 1.0f);
+
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index a978d483a..6c20d6006 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -211,6 +211,10 @@ enum { /* DSM bind states */
/* 12 occupied by CRC */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
+#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
+ 'armed' (PWM enabled) state */
+#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
+
/* autopilot control values, -10000..10000 */
#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 6752e7b4b..9e5d7e7e2 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -570,6 +570,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
dsm_bind(value & 0x0f, (value >> 4) & 0xF);
break;
+ case PX4IO_P_SETUP_FORCE_SAFETY_OFF:
+ if (value == PX4IO_FORCE_SAFETY_MAGIC) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
+ }
+ break;
+
default:
return -1;
}
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 41e2148ac..e260aae45 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -627,39 +627,39 @@ Sensors::parameters_update()
/* channel mapping */
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_pitch, &(_parameters.rc_map_pitch)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_yaw, &(_parameters.rc_map_yaw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_throttle, &(_parameters.rc_map_throttle)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_loiter_sw, &(_parameters.rc_map_loiter_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
@@ -725,12 +725,12 @@ Sensors::parameters_update()
/* scaling of ADC ticks to battery voltage */
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
/* scaling of ADC ticks to battery current */
if (param_get(_parameter_handles.battery_current_scaling, &(_parameters.battery_current_scaling)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));
@@ -1242,7 +1242,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
_last_adc = t;
- if (_battery_status.voltage_v > 0.0f) {
+ if (_battery_status.voltage_filtered_v > BATT_V_IGNORE_THRESHOLD) {
/* announce the battery status if needed, just publish else */
if (_battery_pub > 0) {
orb_publish(ORB_ID(battery_status), _battery_pub, &_battery_status);
@@ -1527,12 +1527,10 @@ Sensors::task_main()
while (!_task_should_exit) {
- /* wait for up to 100ms for data */
- int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+ /* wait for up to 50ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
- /* timed out - periodic check for _task_should_exit, etc. */
- if (pret == 0)
- continue;
+ /* if pret == 0 it timed out - periodic check for _task_should_exit, etc. */
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1571,7 +1569,7 @@ Sensors::task_main()
perf_end(_loop_perf);
}
- printf("[sensors] exiting.\n");
+ warnx("[sensors] exiting.");
_sensors_task = -1;
_exit(0);
diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c
index ec2bc3a9a..702e435ac 100644
--- a/src/modules/systemlib/system_params.c
+++ b/src/modules/systemlib/system_params.c
@@ -62,12 +62,23 @@ PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);
/**
- * Set usage of IO board
- *
- * Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up.
- *
- * @min 0
- * @max 1
- * @group System
- */
+* Set usage of IO board
+*
+* Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up.
+*
+* @min 0
+* @max 1
+* @group System
+*/
PARAM_DEFINE_INT32(SYS_USE_IO, 1);
+
+/**
+* Set restart type
+*
+* Set by px4io to indicate type of restart
+*
+* @min 0
+* @max 2
+* @group System
+*/
+PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 48af4c9e2..435230432 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -69,6 +69,8 @@ typedef enum {
MAIN_STATE_MAX
} main_state_t;
+// If you change the order, add or remove arming_state_t states make sure to update the arrays
+// in state_machine_helper.cpp as well.
typedef enum {
ARMING_STATE_INIT = 0,
ARMING_STATE_STANDBY,
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
index 64ee544a2..02d1af481 100644
--- a/src/modules/unit_test/unit_test.cpp
+++ b/src/modules/unit_test/unit_test.cpp
@@ -32,17 +32,10 @@
*
****************************************************************************/
-/**
- * @file unit_test.cpp
- * A unit test library.
- *
- */
-
#include "unit_test.h"
#include <systemlib/err.h>
-
UnitTest::UnitTest()
{
}
@@ -51,15 +44,15 @@ UnitTest::~UnitTest()
{
}
-void
-UnitTest::print_results(const char* result)
+void UnitTest::printResults(void)
+{
+ warnx(mu_tests_failed() ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
+ warnx(" Tests passed : %d", mu_tests_passed());
+ warnx(" Tests failed : %d", mu_tests_failed());
+ warnx(" Assertions : %d", mu_assertion());
+}
+
+void UnitTest::printAssert(const char* msg, const char* test, const char* file, int line)
{
- if (result != 0) {
- warnx("Failed: %s:%d", mu_last_test(), mu_line());
- warnx("%s", result);
- } else {
- warnx("ALL TESTS PASSED");
- warnx(" Tests run : %d", mu_tests_run());
- warnx(" Assertion : %d", mu_assertion());
- }
+ warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
}
diff --git a/src/modules/unit_test/unit_test.h b/src/modules/unit_test/unit_test.h
index 3020734f4..32eb8c308 100644
--- a/src/modules/unit_test/unit_test.h
+++ b/src/modules/unit_test/unit_test.h
@@ -32,62 +32,55 @@
*
****************************************************************************/
-/**
- * @file unit_test.h
- * A unit test library based on MinUnit (http://www.jera.com/techinfo/jtns/jtn002.html).
- *
- */
-
#ifndef UNIT_TEST_H_
-#define UNIT_TEST_
+#define UNIT_TEST_H_
#include <systemlib/err.h>
-
class __EXPORT UnitTest
{
public:
-#define xstr(s) str(s)
-#define str(s) #s
#define INLINE_GLOBAL(type,func) inline type& func() { static type x; return x; }
INLINE_GLOBAL(int, mu_tests_run)
+INLINE_GLOBAL(int, mu_tests_failed)
+INLINE_GLOBAL(int, mu_tests_passed)
INLINE_GLOBAL(int, mu_assertion)
INLINE_GLOBAL(int, mu_line)
INLINE_GLOBAL(const char*, mu_last_test)
-#define mu_assert(message, test) \
- do \
- { \
- if (!(test)) \
- return __FILE__ ":" xstr(__LINE__) " " message " (" #test ")"; \
- else \
- mu_assertion()++; \
- } while (0)
-
-
-#define mu_run_test(test) \
-do \
-{ \
- const char *message; \
- mu_last_test() = #test; \
- mu_line() = __LINE__; \
- message = test(); \
- mu_tests_run()++; \
- if (message) \
- return message; \
-} while (0)
-
-
-public:
UnitTest();
virtual ~UnitTest();
- virtual const char* run_tests() = 0;
- virtual void print_results(const char* result);
-};
-
+ virtual void runTests(void) = 0;
+ void printResults(void);
+
+ void printAssert(const char* msg, const char* test, const char* file, int line);
+
+#define ut_assert(message, test) \
+ do { \
+ if (!(test)) { \
+ printAssert(message, #test, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ mu_assertion()++; \
+ } \
+ } while (0)
+
+#define ut_run_test(test) \
+ do { \
+ warnx("RUNNING TEST: %s", #test); \
+ mu_tests_run()++; \
+ if (!test()) { \
+ warnx("TEST FAILED: %s", #test); \
+ mu_tests_failed()++; \
+ } else { \
+ warnx("TEST PASSED: %s", #test); \
+ mu_tests_passed()++; \
+ } \
+ } while (0)
+};
#endif /* UNIT_TEST_H_ */
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
index 476015f3e..e6d4b763b 100644
--- a/src/systemcmds/config/config.c
+++ b/src/systemcmds/config/config.c
@@ -121,7 +121,7 @@ do_device(int argc, char *argv[])
errx(ret,"uORB publications could not be unblocked");
} else {
- errx("no valid command: %s", argv[1]);
+ errx(1, "no valid command: %s", argv[1]);
}
}