aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-14 10:38:34 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-14 10:38:34 +0200
commit51a4ef5de1bc542ac4f7072d95250cd62ea73ed6 (patch)
treeb71db4faea6a0ac39e4fa28481421a2acc13a896 /src/modules/commander
parent5e0911046173e01a6c66b91d3e38212e093159d0 (diff)
parentddc8f1fa5f5b88549af5e4f5f46c751a5f3af3ce (diff)
downloadpx4-firmware-51a4ef5de1bc542ac4f7072d95250cd62ea73ed6.tar.gz
px4-firmware-51a4ef5de1bc542ac4f7072d95250cd62ea73ed6.tar.bz2
px4-firmware-51a4ef5de1bc542ac4f7072d95250cd62ea73ed6.zip
merged upstream/master into sbus2_sensorssbus2_sensors
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp82
-rw-r--r--src/modules/commander/accelerometer_calibration.h3
-rw-r--r--src/modules/commander/airspeed_calibration.cpp144
-rw-r--r--src/modules/commander/airspeed_calibration.h2
-rw-r--r--src/modules/commander/baro_calibration.cpp2
-rw-r--r--src/modules/commander/baro_calibration.h2
-rw-r--r--src/modules/commander/calibration_messages.h3
-rw-r--r--src/modules/commander/calibration_routines.cpp12
-rw-r--r--src/modules/commander/calibration_routines.h3
-rw-r--r--src/modules/commander/commander.cpp1671
-rw-r--r--src/modules/commander/commander_helper.cpp135
-rw-r--r--src/modules/commander/commander_helper.h23
-rw-r--r--src/modules/commander/commander_params.c47
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp3
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp534
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h2
-rw-r--r--src/modules/commander/gyro_calibration.cpp18
-rw-r--r--src/modules/commander/mag_calibration.cpp47
-rw-r--r--src/modules/commander/mag_calibration.h2
-rw-r--r--src/modules/commander/module.mk4
-rw-r--r--src/modules/commander/px4_custom_mode.h9
-rw-r--r--src/modules/commander/rc_calibration.cpp6
-rw-r--r--src/modules/commander/state_machine_helper.cpp1031
-rw-r--r--src/modules/commander/state_machine_helper.h27
24 files changed, 2297 insertions, 1515 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 5eeca5a1a..7a4e7a766 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -131,6 +130,7 @@
#include <fcntl.h>
#include <sys/prctl.h>
#include <math.h>
+#include <float.h>
#include <mathlib/mathlib.h>
#include <string.h>
#include <drivers/drv_hrt.h>
@@ -158,6 +158,8 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
int do_accel_calibration(int mavlink_fd)
{
+ int fd;
+
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
struct accel_scale accel_scale = {
@@ -172,7 +174,7 @@ int do_accel_calibration(int mavlink_fd)
int res = OK;
/* reset all offsets to zero and all scales to one */
- int fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, 0);
res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
close(fd);
@@ -194,15 +196,13 @@ int do_accel_calibration(int mavlink_fd)
int32_t board_rotation_int;
param_get(board_rotation_h, &(board_rotation_int));
enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
- math::Matrix board_rotation(3, 3);
+ math::Matrix<3, 3> board_rotation;
get_rot_matrix(board_rotation_id, &board_rotation);
- math::Matrix board_rotation_t = board_rotation.transpose();
- math::Vector3 accel_offs_vec;
- accel_offs_vec.set(&accel_offs[0]);
- math::Vector3 accel_offs_rotated = board_rotation_t * accel_offs_vec;
- math::Matrix accel_T_mat(3, 3);
- accel_T_mat.set(&accel_T[0][0]);
- math::Matrix accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+ math::Matrix<3, 3> board_rotation_t = board_rotation.transposed();
+ math::Vector<3> accel_offs_vec(&accel_offs[0]);
+ math::Vector<3> accel_offs_rotated = board_rotation_t *accel_offs_vec;
+ math::Matrix<3, 3> accel_T_mat(&accel_T[0][0]);
+ math::Matrix<3, 3> accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation;
accel_scale.x_offset = accel_offs_rotated(0);
accel_scale.x_scale = accel_T_rotated(0, 0);
@@ -225,7 +225,7 @@ int do_accel_calibration(int mavlink_fd)
if (res == OK) {
/* apply new scaling and offsets */
- int fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, 0);
res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
close(fd);
@@ -279,11 +279,13 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
}
- if (old_done_count != done_count)
+ if (old_done_count != done_count) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
+ }
- if (done)
+ if (done) {
break;
+ }
mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
(!data_collected[0]) ? "x+ " : "",
@@ -313,7 +315,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
(double)accel_ref[orient][2]);
data_collected[orient] = true;
- tune_neutral();
+ tune_neutral(true);
}
close(sensor_combined_sub);
@@ -382,11 +384,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
- if (d > still_thr2 * 8.0f)
+ if (d > still_thr2 * 8.0f) {
d = still_thr2 * 8.0f;
+ }
- if (d > accel_disp[i])
+ if (d > accel_disp[i]) {
accel_disp[i] = d;
+ }
}
/* still detector with hysteresis */
@@ -434,33 +438,39 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 0; // [ g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 0; // [ g, 0, 0 ]
+ }
if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 1; // [ -g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 1; // [ -g, 0, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 2; // [ 0, g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 2; // [ 0, g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 3; // [ 0, -g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 3; // [ 0, -g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
- return 4; // [ 0, 0, g ]
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr) {
+ return 4; // [ 0, 0, g ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
- return 5; // [ 0, 0, -g ]
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr) {
+ return 5; // [ 0, 0, -g ]
+ }
mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
@@ -487,8 +497,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
struct sensor_combined_s sensor;
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- for (int i = 0; i < 3; i++)
+ for (int i = 0; i < 3; i++) {
accel_sum[i] += sensor.accelerometer_m_s2[i];
+ }
count++;
@@ -497,8 +508,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
continue;
}
- if (errcount > samples_num / 10)
+ if (errcount > samples_num / 10) {
return ERROR;
+ }
}
for (int i = 0; i < 3; i++) {
@@ -514,8 +526,9 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0f)
- return ERROR; // Singular matrix
+ if (fabsf(det) < FLT_EPSILON) {
+ return ERROR; // Singular matrix
+ }
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
@@ -551,8 +564,9 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* calculate inverse matrix for A */
float mat_A_inv[3][3];
- if (mat_invert3(mat_A, mat_A_inv) != OK)
+ if (mat_invert3(mat_A, mat_A_inv) != OK) {
return ERROR;
+ }
/* copy results to accel_T */
for (int i = 0; i < 3; i++) {
diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h
index 1cf9c0977..6b7e16d44 100644
--- a/src/modules/commander/accelerometer_calibration.h
+++ b/src/modules/commander/accelerometer_calibration.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 1809f9688..598cfe9e2 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. 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
@@ -51,6 +51,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
+#include <systemlib/airspeed.h>
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -64,38 +65,58 @@ int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "don't move system");
- const int calibration_count = 2500;
+ const unsigned calibration_count = 2000;
int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
struct differential_pressure_s diff_pres;
- int calibration_counter = 0;
float diff_pres_offset = 0.0f;
/* Reset sensor parameters */
struct airspeed_scale airscale = {
- 0.0f,
+ diff_pres_offset,
1.0f,
};
bool paramreset_successful = false;
int fd = open(AIRSPEED_DEVICE_PATH, 0);
+
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
+
close(fd);
}
if (!paramreset_successful) {
- warn("WARNING: failed to set scale / offsets for airspeed sensor");
- mavlink_log_critical(mavlink_fd, "could not reset dpress sensor");
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
- return ERROR;
+
+ /* only warn if analog scaling is zero */
+ float analog_scaling = 0.0f;
+ param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling));
+ if (fabsf(analog_scaling) < 0.1f) {
+ mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]");
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ /* set scaling offset parameter */
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
}
+ unsigned calibration_counter = 0;
+
+ mavlink_log_critical(mavlink_fd, "Ensure sensor is not measuring wind");
+ usleep(500 * 1000);
+
while (calibration_counter < calibration_count) {
/* wait blocking for new data */
@@ -107,11 +128,13 @@ int do_airspeed_calibration(int mavlink_fd)
if (poll_ret) {
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
+
+ diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
- mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ if (calibration_counter % (calibration_count / 20) == 0) {
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 80) / calibration_count);
+ }
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
@@ -125,6 +148,16 @@ int do_airspeed_calibration(int mavlink_fd)
if (isfinite(diff_pres_offset)) {
+ int fd_scale = open(AIRSPEED_DEVICE_PATH, 0);
+ airscale.offset_pa = diff_pres_offset;
+ if (fd_scale > 0) {
+ if (OK != ioctl(fd_scale, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
+ mavlink_log_critical(mavlink_fd, "airspeed offset update failed");
+ }
+
+ close(fd_scale);
+ }
+
if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
close(diff_pres_sub);
@@ -141,14 +174,91 @@ int do_airspeed_calibration(int mavlink_fd)
return ERROR;
}
- mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- tune_neutral();
- close(diff_pres_sub);
- return OK;
-
} else {
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
close(diff_pres_sub);
return ERROR;
}
+
+ mavlink_log_critical(mavlink_fd, "Offset of %d Pa, create airflow now!", (int)diff_pres_offset);
+
+ /* wait 500 ms to ensure parameter propagated through the system */
+ usleep(500 * 1000);
+
+ calibration_counter = 0;
+ const int maxcount = 3000;
+
+ /* just take a few samples and make sure pitot tubes are not reversed, timeout after ~30 seconds */
+ while (calibration_counter < maxcount) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = diff_pres_sub;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+
+ calibration_counter++;
+
+ if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
+ if (calibration_counter % 100 == 0) {
+ mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ }
+ continue;
+ }
+
+ /* do not allow negative values */
+ if (diff_pres.differential_pressure_raw_pa < 0.0f) {
+ mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa);
+ close(diff_pres_sub);
+
+ /* the user setup is wrong, wipe the calibration to force a proper re-calibration */
+
+ diff_pres_offset = 0.0f;
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ /* save */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 0);
+ (void)param_save_default();
+
+ close(diff_pres_sub);
+
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ return ERROR;
+ } else {
+ mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ break;
+ }
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+ }
+
+ if (calibration_counter == maxcount) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 100);
+
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+ tune_neutral(true);
+ close(diff_pres_sub);
+ return OK;
}
diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h
index 71c701fc2..8c6b65ff1 100644
--- a/src/modules/commander/airspeed_calibration.h
+++ b/src/modules/commander/airspeed_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. 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
diff --git a/src/modules/commander/baro_calibration.cpp b/src/modules/commander/baro_calibration.cpp
index 3123c4087..da98644b4 100644
--- a/src/modules/commander/baro_calibration.cpp
+++ b/src/modules/commander/baro_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/baro_calibration.h b/src/modules/commander/baro_calibration.h
index bc42bc6cf..ce78ae700 100644
--- a/src/modules/commander/baro_calibration.h
+++ b/src/modules/commander/baro_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h
index fd8b8564d..b1e209efc 100644
--- a/src/modules/commander/calibration_messages.h
+++ b/src/modules/commander/calibration_messages.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp
index be38ea104..5796204bf 100644
--- a/src/modules/commander/calibration_routines.cpp
+++ b/src/modules/commander/calibration_routines.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012 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
@@ -40,6 +39,7 @@
*/
#include <math.h>
+#include <float.h>
#include "calibration_routines.h"
@@ -170,7 +170,7 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
float aA, aB, aC, nA, nB, nC, dA, dB, dC;
//Iterate N times, ignore stop condition.
- int n = 0;
+ unsigned int n = 0;
while (n < max_iterations) {
n++;
@@ -179,9 +179,9 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
aA = Q2 + 16.0f * (A2 - 2.0f * A * x_sum + x_sum2);
aB = Q2 + 16.0f * (B2 - 2.0f * B * y_sum + y_sum2);
aC = Q2 + 16.0f * (C2 - 2.0f * C * z_sum + z_sum2);
- aA = (aA == 0.0f) ? 1.0f : aA;
- aB = (aB == 0.0f) ? 1.0f : aB;
- aC = (aC == 0.0f) ? 1.0f : aC;
+ aA = (fabsf(aA) < FLT_EPSILON) ? 1.0f : aA;
+ aB = (fabsf(aB) < FLT_EPSILON) ? 1.0f : aB;
+ aC = (fabsf(aC) < FLT_EPSILON) ? 1.0f : aC;
//Compute next iteration
nA = A - ((F2 + 16.0f * (B * XY + C * XZ + x_sum * (-A2 - Q0) + A * (x_sum2 + Q1 - C * z_sum - B * y_sum))) / aA);
diff --git a/src/modules/commander/calibration_routines.h b/src/modules/commander/calibration_routines.h
index e3e7fbafd..3c8e49ee9 100644
--- a/src/modules/commander/calibration_routines.h
+++ b/src/modules/commander/calibration_routines.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012 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/commander/commander.cpp b/src/modules/commander/commander.cpp
index 54219a34a..0c4d48dea 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1,11 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Anton Babushkin <anton.babushkin@me.com>
+ * 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
@@ -38,8 +33,13 @@
/**
* @file commander.cpp
- * Main system state machine implementation.
+ * Main fail-safe handling.
*
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
@@ -52,6 +52,7 @@
#include <fcntl.h>
#include <errno.h>
#include <systemlib/err.h>
+#include <systemlib/circuit_breaker.h>
#include <debug.h>
#include <sys/prctl.h>
#include <sys/stat.h>
@@ -67,15 +68,19 @@
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/subsystem_info.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/safety.h>
+#include <uORB/topics/system_power.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+#include <uORB/topics/telemetry_status.h>
#include <drivers/drv_led.h>
#include <drivers/drv_hrt.h>
@@ -87,6 +92,8 @@
#include <systemlib/err.h>
#include <systemlib/cpuload.h>
#include <systemlib/rc_check.h>
+#include <systemlib/state_table.h>
+#include <dataman/dataman.h>
#include "px4_custom_mode.h"
#include "commander_helper.h"
@@ -113,14 +120,16 @@ extern struct system_load_s system_load;
#define MAVLINK_OPEN_INTERVAL 50000
-#define STICK_ON_OFF_LIMIT 0.75f
-#define STICK_THRUST_RANGE 1.0f
+#define STICK_ON_OFF_LIMIT 0.9f
#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 1000000 /**< consider the local or global position estimate invalid after 1s */
-#define RC_TIMEOUT 100000
-#define DIFFPRESS_TIMEOUT 2000000
+#define POSITION_TIMEOUT (600 * 1000) /**< consider the local or global position estimate invalid after 600ms */
+#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
+#define RC_TIMEOUT 500000
+#define DL_TIMEOUT 5 * 1000* 1000
+#define OFFBOARD_TIMEOUT 500000
+#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
#define PRINT_MODE_REJECT_INTERVAL 2000000
@@ -138,7 +147,7 @@ enum MAV_MODE_FLAG {
};
/* Mavlink file descriptors */
-static int mavlink_fd;
+static int mavlink_fd = 0;
/* flags */
static bool commander_initialized = false;
@@ -153,16 +162,14 @@ static uint64_t last_print_mode_reject_time = 0;
static bool on_usb_power = false;
static float takeoff_alt = 5.0f;
+static int parachute_enabled = 0;
+static float eph_epv_threshold = 5.0f;
static struct vehicle_status_s status;
-
-/* armed topic */
static struct actuator_armed_s armed;
-
static struct safety_s safety;
-
-/* flags for control apps */
-struct vehicle_control_mode_s control_mode;
+static struct vehicle_control_mode_s control_mode;
+static struct offboard_control_setpoint_s sp_offboard;
/* tasks waiting for low prio thread */
typedef enum {
@@ -199,7 +206,7 @@ void usage(const char *reason);
/**
* React to commands that are sent e.g. from the mavlink module.
*/
-void handle_command(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed);
+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);
/**
* Mainloop of commander.
@@ -210,9 +217,11 @@ void control_status_leds(vehicle_status_s *status, const actuator_armed_s *actua
void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed);
-void check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *current_status);
+void check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *status);
+
+transition_result_t set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoint_s *sp_man);
-transition_result_t check_main_state_machine(struct vehicle_status_s *current_status);
+void set_control_mode();
void print_reject_mode(struct vehicle_status_s *current_status, const char *msg);
@@ -220,11 +229,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.
*/
@@ -235,8 +243,9 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
int commander_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
usage("missing command");
+ }
if (!strcmp(argv[1], "start")) {
@@ -250,7 +259,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 3000,
+ 2950,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -263,8 +272,9 @@ int commander_main(int argc, char *argv[])
if (!strcmp(argv[1], "stop")) {
- if (!thread_running)
+ if (!thread_running) {
errx(0, "commander already stopped");
+ }
thread_should_exit = true;
@@ -278,25 +288,32 @@ int commander_main(int argc, char *argv[])
exit(0);
}
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("\tcommander is running");
- print_status();
+ /* commands needing the app to run below */
+ if (!thread_running) {
+ warnx("\tcommander not started");
+ exit(1);
+ }
- } else {
- warnx("\tcommander not started");
- }
+ if (!strcmp(argv[1], "status")) {
+ print_status();
+ exit(0);
+ }
+ if (!strcmp(argv[1], "check")) {
+ int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0);
+ int checkres = prearm_check(&status, mavlink_fd_local);
+ close(mavlink_fd_local);
+ warnx("FINAL RESULT: %s", (checkres == 0) ? "OK" : "FAILED");
exit(0);
}
if (!strcmp(argv[1], "arm")) {
- arm();
+ arm_disarm(true, mavlink_fd, "command line");
exit(0);
}
if (!strcmp(argv[1], "disarm")) {
- disarm();
+ arm_disarm(false, mavlink_fd, "command line");
exit(0);
}
@@ -306,8 +323,9 @@ int commander_main(int argc, char *argv[])
void usage(const char *reason)
{
- if (reason)
+ if (reason) {
fprintf(stderr, "%s\n", reason);
+ }
fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
exit(1);
@@ -315,6 +333,7 @@ void usage(const char *reason)
void print_status()
{
+ warnx("type: %s", (status.is_rotary_wing) ? "ROTARY" : "PLANE");
warnx("usb powered: %s", (on_usb_power) ? "yes" : "no");
/* read all relevant states */
@@ -364,277 +383,339 @@ void print_status()
warnx("arming: %s", armed_str);
}
-static orb_advert_t control_mode_pub;
static orb_advert_t status_pub;
-int arm()
+transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char *armedBy)
{
- int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
- return 0;
- } else {
- return 1;
- }
-}
+ // 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_local);
-int disarm()
-{
- int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
+ mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
- return 0;
- } else {
- return 1;
+ } else if (arming_res == TRANSITION_DENIED) {
+ tune_negative(true);
}
+
+ return arming_res;
}
-void handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed)
+bool handle_command(struct vehicle_status_s *status_local, const struct safety_s *safety_local,
+ struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local,
+ struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
{
- /* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ /* only handle commands that are meant to be handled by this system and component */
+ if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
+ return false;
+ }
- /* only handle high-priority commands here */
+ /* result of the command */
+ enum VEHICLE_CMD_RESULT cmd_result = VEHICLE_CMD_RESULT_UNSUPPORTED;
/* request to set different system mode */
switch (cmd->command) {
case VEHICLE_CMD_DO_SET_MODE: {
- uint8_t base_mode = (uint8_t) cmd->param1;
- uint8_t custom_main_mode = (uint8_t) cmd->param2;
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- /* set HIL state */
- hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
- int hil_ret = hil_state_transition(new_hil_state, status_pub, status, control_mode_pub, control_mode, mavlink_fd);
-
- /* if HIL got enabled, reset battery status state */
- if (hil_ret == OK && control_mode->flag_system_hil_enabled) {
- /* reset the arming mode to disarmed */
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_STANDBY, armed);
+ uint8_t base_mode = (uint8_t)cmd->param1;
+ uint8_t custom_main_mode = (uint8_t)cmd->param2;
- if (arming_res != TRANSITION_DENIED) {
- mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
+ transition_result_t arming_ret = TRANSITION_NOT_CHANGED;
- } else {
- mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state");
- }
- }
-
- // 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) && !control_mode->flag_system_hil_enabled) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
- arming_res = TRANSITION_DENIED;
-
- } else {
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
- }
+ transition_result_t main_ret = TRANSITION_NOT_CHANGED;
- 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, control_mode, new_arming_state, armed);
-
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] DISARMED by command");
- }
-
- } else {
- arming_res = TRANSITION_NOT_CHANGED;
- }
- }
+ /* set HIL state */
+ hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
+ transition_result_t hil_ret = hil_state_transition(new_hil_state, status_pub, status_local, mavlink_fd);
- /* set main state */
- transition_result_t main_res = TRANSITION_DENIED;
+ // Transition the arming state
+ arming_ret = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
/* use autopilot-specific mode */
if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
/* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
- /* SEATBELT */
- main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
+ /* ALTCTL */
+ main_ret = main_state_transition(status_local, MAIN_STATE_ALTCTL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
+ /* POSCTL */
+ main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
+ /* ACRO */
+ main_ret = main_state_transition(status_local, MAIN_STATE_ACRO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
+ /* OFFBOARD */
+ main_ret = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
}
} else {
/* use base mode */
if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
/* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ /* POSCTL */
+ main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL);
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
/* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL);
}
}
}
- if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ if (hil_ret != TRANSITION_DENIED && arming_ret != TRANSITION_DENIED && main_ret != TRANSITION_DENIED) {
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
-
- break;
}
+ break;
+
+ case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
+ // Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
+ // for logic state parameters
- case VEHICLE_CMD_NAV_TAKEOFF: {
- if (armed->armed) {
- transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
+ if (static_cast<int>(cmd->param1 + 0.5f) != 0 && static_cast<int>(cmd->param1 + 0.5f) != 1) {
+ mavlink_log_critical(mavlink_fd, "Unsupported ARM_DISARM param: %.3f", (double)cmd->param1);
- if (nav_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
+ } else {
+
+ bool cmd_arms = (static_cast<int>(cmd->param1 + 0.5f) == 1);
+
+ // Flick to inair restore first if this comes from an onboard system
+ if (cmd->source_system == status_local->system_id && cmd->source_component == status_local->component_id) {
+ status_local->arming_state = ARMING_STATE_IN_AIR_RESTORE;
}
- if (nav_res != TRANSITION_DENIED) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ transition_result_t arming_res = arm_disarm(cmd_arms, mavlink_fd, "arm/disarm component command");
+
+ if (arming_res == TRANSITION_DENIED) {
+ mavlink_log_critical(mavlink_fd, "REJECTING component arm cmd");
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
}
+ }
+ }
+ break;
+
+ case VEHICLE_CMD_OVERRIDE_GOTO: {
+ // TODO listen vehicle_command topic directly from navigator (?)
+
+ // Increase by 0.5f and rely on the integer cast
+ // implicit floor(). This is the *safest* way to
+ // convert from floats representing small ints to actual ints.
+ unsigned int mav_goto = (cmd->param1 + 0.5f);
+
+ if (mav_goto == 0) { // MAV_GOTO_DO_HOLD
+ status_local->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ mavlink_log_critical(mavlink_fd, "Pause mission cmd");
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE
+ status_local->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ mavlink_log_critical(mavlink_fd, "Continue mission cmd");
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- /* reject TAKEOFF not armed */
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f",
+ (double)cmd->param1,
+ (double)cmd->param2,
+ (double)cmd->param3,
+ (double)cmd->param4,
+ (double)cmd->param5,
+ (double)cmd->param6,
+ (double)cmd->param7);
+ }
+ }
+ break;
+
+#if 0
+ /* Flight termination */
+ case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
+
+ //XXX: to enable the parachute, a param needs to be set
+ //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO
+ if (armed_local->armed && cmd->param3 > 0.5 && parachute_enabled) {
+ transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION);
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ /* reject parachute depoyment not armed */
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
- break;
}
+ break;
+#endif
- case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+ case VEHICLE_CMD_DO_SET_HOME: {
+ bool use_current = cmd->param1 > 0.5f;
+
+ if (use_current) {
+ /* use current position */
+ if (status_local->condition_global_position_valid) {
+ home->lat = global_pos->lat;
+ home->lon = global_pos->lon;
+ home->alt = global_pos->alt;
- if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
- if (safety->safety_switch_available && !safety->safety_off) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
- arming_res = TRANSITION_DENIED;
+ home->timestamp = hrt_absolute_time();
+
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- arming_res = arming_state_transition(status, safety, control_mode, ARMING_STATE_ARMED, armed);
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
- if (arming_res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#audio: ARMED by component arm cmd");
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ } else {
+ /* use specified position */
+ home->lat = cmd->param5;
+ home->lon = cmd->param6;
+ home->alt = cmd->param7;
+
+ home->timestamp = hrt_absolute_time();
+
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
+ }
+
+ if (cmd_result == VEHICLE_CMD_RESULT_ACCEPTED) {
+ warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home->lat, home->lon, (double)home->alt);
+ mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home->lat, home->lon, (double)home->alt);
+
+ /* announce new home position */
+ if (*home_pub > 0) {
+ orb_publish(ORB_ID(home_position), *home_pub, home);
} else {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ *home_pub = orb_advertise(ORB_ID(home_position), home);
}
+
+ /* mark home position as set */
+ status_local->condition_home_position_valid = true;
}
}
break;
+ case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
+ case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
+ case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
+ case VEHICLE_CMD_PREFLIGHT_STORAGE:
+ /* ignore commands that handled in low prio loop */
+ break;
+
default:
+ /* Warn about unsupported commands, this makes sense because only commands
+ * to this component ID (or all) are passed by mavlink. */
+ answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
- /* supported command handling stop */
- if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
- tune_positive();
-
- } else if (result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
- /* we do not care in the high prio loop about commands we don't know */
- } else {
- tune_negative();
-
- if (result == VEHICLE_CMD_RESULT_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd->command);
-
- } else if (result == VEHICLE_CMD_RESULT_FAILED) {
- mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd->command);
-
- } else if (result == VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED) {
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
-
- }
+ if (cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ /* already warned about unsupported commands in "default" case */
+ answer_command(*cmd, cmd_result);
}
/* send any requested ACKs */
- if (cmd->confirmation > 0 && result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ if (cmd->confirmation > 0 && cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* send acknowledge command */
// XXX TODO
}
+ return true;
}
int commander_thread_main(int argc, char *argv[])
{
/* not yet initialized */
commander_initialized = false;
- bool home_position_set = false;
- bool battery_tune_played = false;
bool arm_tune_played = false;
+ bool was_armed = false;
/* set parameters */
param_t _param_sys_type = param_find("MAV_TYPE");
param_t _param_system_id = param_find("MAV_SYS_ID");
param_t _param_component_id = param_find("MAV_COMP_ID");
param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT");
+ param_t _param_enable_parachute = param_find("NAV_PARACHUTE_EN");
+ param_t _param_enable_datalink_loss = param_find("COM_DL_LOSS_EN");
/* welcome user */
warnx("starting");
+ const char *main_states_str[MAIN_STATE_MAX];
+ main_states_str[MAIN_STATE_MANUAL] = "MANUAL";
+ main_states_str[MAIN_STATE_ALTCTL] = "ALTCTL";
+ main_states_str[MAIN_STATE_POSCTL] = "POSCTL";
+ main_states_str[MAIN_STATE_AUTO_MISSION] = "AUTO_MISSION";
+ main_states_str[MAIN_STATE_AUTO_LOITER] = "AUTO_LOITER";
+ main_states_str[MAIN_STATE_AUTO_RTL] = "AUTO_RTL";
+ main_states_str[MAIN_STATE_ACRO] = "ACRO";
+ main_states_str[MAIN_STATE_OFFBOARD] = "OFFBOARD";
+
+ const char *arming_states_str[ARMING_STATE_MAX];
+ arming_states_str[ARMING_STATE_INIT] = "INIT";
+ arming_states_str[ARMING_STATE_STANDBY] = "STANDBY";
+ arming_states_str[ARMING_STATE_ARMED] = "ARMED";
+ arming_states_str[ARMING_STATE_ARMED_ERROR] = "ARMED_ERROR";
+ arming_states_str[ARMING_STATE_STANDBY_ERROR] = "STANDBY_ERROR";
+ arming_states_str[ARMING_STATE_REBOOT] = "REBOOT";
+ arming_states_str[ARMING_STATE_IN_AIR_RESTORE] = "IN_AIR_RESTORE";
+
+ const char *nav_states_str[NAVIGATION_STATE_MAX];
+ nav_states_str[NAVIGATION_STATE_MANUAL] = "MANUAL";
+ nav_states_str[NAVIGATION_STATE_ALTCTL] = "ALTCTL";
+ nav_states_str[NAVIGATION_STATE_POSCTL] = "POSCTL";
+ nav_states_str[NAVIGATION_STATE_AUTO_MISSION] = "AUTO_MISSION";
+ nav_states_str[NAVIGATION_STATE_AUTO_LOITER] = "AUTO_LOITER";
+ nav_states_str[NAVIGATION_STATE_AUTO_RTL] = "AUTO_RTL";
+ nav_states_str[NAVIGATION_STATE_AUTO_RTGS] = "AUTO_RTGS";
+ nav_states_str[NAVIGATION_STATE_ACRO] = "ACRO";
+ nav_states_str[NAVIGATION_STATE_LAND] = "LAND";
+ nav_states_str[NAVIGATION_STATE_DESCEND] = "DESCEND";
+ nav_states_str[NAVIGATION_STATE_TERMINATION] = "TERMINATION";
+ nav_states_str[NAVIGATION_STATE_OFFBOARD] = "OFFBOARD";
+
/* pthread for slow low prio thread */
pthread_t commander_low_prio_thread;
/* initialize */
if (led_init() != 0) {
- warnx("ERROR: Failed to initialize leds");
+ warnx("ERROR: LED INIT FAIL");
}
if (buzzer_init() != OK) {
- warnx("ERROR: Failed to initialize buzzer");
+ warnx("ERROR: BUZZER INIT FAIL");
}
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
- /* Main state machine */
- /* make sure we are in preflight state */
+ /* vehicle status topic */
memset(&status, 0, sizeof(status));
status.condition_landed = true; // initialize to safe value
// We want to accept RC inputs as default
status.rc_input_blocked = false;
-
- /* armed topic */
- orb_advert_t armed_pub;
- /* Initialize armed with all false */
- memset(&armed, 0, sizeof(armed));
-
- /* Initialize all flags to false */
- memset(&control_mode, 0, sizeof(control_mode));
-
status.main_state = MAIN_STATE_MANUAL;
- status.navigation_state = NAVIGATION_STATE_DIRECT;
+ status.nav_state = NAVIGATION_STATE_MANUAL;
status.arming_state = ARMING_STATE_INIT;
status.hil_state = HIL_STATE_OFF;
+ status.failsafe = false;
/* neither manual nor offboard control commands have been received */
status.offboard_control_signal_found_once = false;
@@ -643,9 +724,7 @@ int commander_thread_main(int argc, char *argv[])
/* mark all signals lost as long as they haven't been found */
status.rc_signal_lost = true;
status.offboard_control_signal_lost = true;
-
- /* allow manual override initially */
- control_mode.flag_external_manual_override_ok = true;
+ status.data_link_lost = true;
/* set battery warning flag */
status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
@@ -654,40 +733,68 @@ int commander_thread_main(int argc, char *argv[])
// XXX for now just set sensors as initialized
status.condition_system_sensors_initialized = true;
- // XXX just disable offboard control for now
- control_mode.flag_control_offboard_enabled = false;
+ status.counter++;
+ status.timestamp = hrt_absolute_time();
- /* advertise to ORB */
- status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
- /* publish current state machine */
+ status.condition_power_input_valid = true;
+ status.avionics_power_rail_voltage = -1.0f;
+
+ // CIRCUIT BREAKERS
+ status.circuit_breaker_engaged_power_check = false;
/* publish initial state */
- status.counter++;
- status.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+ status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+ if (status_pub < 0) {
+ warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
+ warnx("exiting.");
+ exit(ERROR);
+ }
- armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
+ /* armed topic */
+ orb_advert_t armed_pub;
+ /* Initialize armed with all false */
+ memset(&armed, 0, sizeof(armed));
- control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
+ /* vehicle control mode topic */
+ memset(&control_mode, 0, sizeof(control_mode));
+ orb_advert_t control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
+
+ armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
/* home position */
orb_advert_t home_pub = -1;
struct home_position_s home;
memset(&home, 0, sizeof(home));
- if (status_pub < 0) {
- warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
- warnx("exiting.");
- exit(ERROR);
- }
+ /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */
+ orb_advert_t mission_pub = -1;
+ mission_s mission;
+ if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) {
+ if (mission.dataman_id >= 0 && mission.dataman_id <= 1) {
+ warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq);
+ mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d",
+ mission.dataman_id, mission.count, mission.current_seq);
+ } else {
+ const char *missionfail = "reading mission state failed";
+ warnx("%s", missionfail);
+ mavlink_log_critical(mavlink_fd, missionfail);
+
+ /* initialize mission state in dataman */
+ mission.dataman_id = 0;
+ mission.count = 0;
+ mission.current_seq = 0;
+ dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s));
+ }
- mavlink_log_info(mavlink_fd, "[cmd] started");
+ mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
+ orb_publish(ORB_ID(offboard_mission), mission_pub, &mission);
+ }
int ret;
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2900);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
@@ -706,15 +813,15 @@ int commander_thread_main(int argc, char *argv[])
bool low_battery_voltage_actions_done = false;
bool critical_battery_voltage_actions_done = false;
- uint64_t last_idle_time = 0;
- uint64_t start_time = 0;
+ hrt_abstime last_idle_time = 0;
+ hrt_abstime start_time = 0;
bool status_changed = true;
bool param_init_forced = true;
bool updated = false;
- bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+ rc_calibration_check(mavlink_fd);
/* Subscribe to safety topic */
int safety_sub = orb_subscribe(ORB_ID(safety));
@@ -722,6 +829,11 @@ int commander_thread_main(int argc, char *argv[])
safety.safety_switch_available = false;
safety.safety_off = false;
+ /* Subscribe to mission result topic */
+ int mission_result_sub = orb_subscribe(ORB_ID(mission_result));
+ struct mission_result_s mission_result;
+ memset(&mission_result, 0, sizeof(mission_result));
+
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
struct manual_control_setpoint_s sp_man;
@@ -729,13 +841,26 @@ int commander_thread_main(int argc, char *argv[])
/* Subscribe to offboard control data */
int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- struct offboard_control_setpoint_s sp_offboard;
memset(&sp_offboard, 0, sizeof(sp_offboard));
+ /* Subscribe to telemetry status topics */
+ int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
+ uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM];
+ bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM];
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ telemetry_last_heartbeat[i] = 0;
+ telemetry_lost[i] = true;
+ }
+
/* Subscribe to global position */
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
struct vehicle_global_position_s global_position;
memset(&global_position, 0, sizeof(global_position));
+ /* Init EPH and EPV */
+ global_position.eph = 1000.0f;
+ global_position.epv = 1000.0f;
/* Subscribe to local position data */
int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
@@ -783,6 +908,16 @@ int commander_thread_main(int argc, char *argv[])
struct subsystem_info_s info;
memset(&info, 0, sizeof(info));
+ /* Subscribe to position setpoint triplet */
+ int pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
+ struct position_setpoint_triplet_s pos_sp_triplet;
+ memset(&pos_sp_triplet, 0, sizeof(pos_sp_triplet));
+
+ /* Subscribe to system power */
+ int system_power_sub = orb_subscribe(ORB_ID(system_power));
+ struct system_power_s system_power;
+ memset(&system_power, 0, sizeof(system_power));
+
control_status_leds(&status, &armed, true);
/* now initialized */
@@ -791,6 +926,15 @@ int commander_thread_main(int argc, char *argv[])
start_time = hrt_absolute_time();
+ transition_result_t arming_ret;
+
+ int32_t datalink_loss_enabled = false;
+
+ /* check which state machines for changes, clear "changed" flag */
+ bool arming_state_changed = false;
+ bool main_state_changed = false;
+ bool failsafe_old = false;
+
while (!thread_should_exit) {
if (mavlink_fd < 0 && counter % (1000000 / MAVLINK_OPEN_INTERVAL) == 0) {
@@ -798,6 +942,9 @@ int commander_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
+ arming_ret = TRANSITION_NOT_CHANGED;
+
+
/* update parameters */
orb_check(param_changed_sub, &updated);
@@ -819,25 +966,28 @@ int commander_thread_main(int argc, char *argv[])
status.system_type == VEHICLE_TYPE_QUADROTOR ||
status.system_type == VEHICLE_TYPE_HEXAROTOR ||
status.system_type == VEHICLE_TYPE_OCTOROTOR) {
- control_mode.flag_external_manual_override_ok = false;
status.is_rotary_wing = true;
} else {
- control_mode.flag_external_manual_override_ok = true;
status.is_rotary_wing = false;
}
/* check and update system / component ID */
param_get(_param_system_id, &(status.system_id));
param_get(_param_component_id, &(status.component_id));
+
+ status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
+
status_changed = true;
/* re-check RC calibration */
- rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
-
- /* navigation parameters */
- param_get(_param_takeoff_alt, &takeoff_alt);
+ rc_calibration_check(mavlink_fd);
}
+
+ /* navigation parameters */
+ param_get(_param_takeoff_alt, &takeoff_alt);
+ param_get(_param_enable_parachute, &parachute_enabled);
+ param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
}
orb_check(sp_man_sub, &updated);
@@ -852,6 +1002,41 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
}
+ if (sp_offboard.timestamp != 0 &&
+ sp_offboard.timestamp + OFFBOARD_TIMEOUT > hrt_absolute_time()) {
+ if (status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = false;
+ status_changed = true;
+ }
+ } else {
+ if (!status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = true;
+ status_changed = true;
+ }
+ }
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ orb_check(telemetry_subs[i], &updated);
+
+ if (updated) {
+ struct telemetry_status_s telemetry;
+ memset(&telemetry, 0, sizeof(telemetry));
+
+ orb_copy(telemetry_status_orb_id[i], telemetry_subs[i], &telemetry);
+
+ /* perform system checks when new telemetry link connected */
+ if (mavlink_fd &&
+ telemetry_last_heartbeat[i] == 0 &&
+ telemetry.heartbeat_time > 0 &&
+ hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) {
+
+ (void)rc_calibration_check(mavlink_fd);
+ }
+
+ telemetry_last_heartbeat[i] = telemetry.heartbeat_time;
+ }
+ }
+
orb_check(sensor_sub, &updated);
if (updated) {
@@ -864,6 +1049,26 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
}
+ orb_check(system_power_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(system_power), system_power_sub, &system_power);
+
+ if (hrt_elapsed_time(&system_power.timestamp) < 200000) {
+ if (system_power.servo_valid &&
+ !system_power.brick_valid &&
+ !system_power.usb_connected) {
+ /* flying only on servo rail, this is unsafe */
+ status.condition_power_input_valid = false;
+ } else {
+ status.condition_power_input_valid = true;
+ }
+
+ /* copy avionics voltage */
+ status.avionics_power_rail_voltage = system_power.voltage5V_v;
+ }
+ }
+
check_valid(diff_pres.timestamp, DIFFPRESS_TIMEOUT, true, &(status.condition_airspeed_valid), &status_changed);
/* update safety topic */
@@ -872,11 +1077,15 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(safety), safety_sub, &safety);
- // XXX this would be the right approach to do it, but do we *WANT* this?
- // /* disarm if safety is now on and still armed */
- // if (safety.safety_switch_available && !safety.safety_off) {
- // (void)arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
- // }
+ /* disarm if safety is now on and still armed */
+ if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
+ arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+
+ if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) {
+ mavlink_log_info(mavlink_fd, "DISARMED by safety switch");
+ arming_state_changed = true;
+ }
+ }
}
/* update global position estimate */
@@ -887,9 +1096,6 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position);
}
- /* update condition_global_position_valid */
- check_valid(global_position.timestamp, POSITION_TIMEOUT, global_position.valid, &(status.condition_global_position_valid), &status_changed);
-
/* update local position estimate */
orb_check(local_position_sub, &updated);
@@ -898,20 +1104,92 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
}
+ /* update condition_global_position_valid */
+ /* hysteresis for EPH/EPV */
+ bool eph_epv_good;
+
+ if (status.condition_global_position_valid) {
+ if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) {
+ eph_epv_good = false;
+
+ } else {
+ eph_epv_good = true;
+ }
+
+ } else {
+ if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) {
+ eph_epv_good = true;
+
+ } else {
+ eph_epv_good = false;
+ }
+ }
+
+ check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed);
+
+ /* check if GPS fix is ok */
+
+ /* update home position */
+ if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+
+ home.lat = global_position.lat;
+ home.lon = global_position.lon;
+ home.alt = global_position.alt;
+
+ home.x = local_position.x;
+ home.y = local_position.y;
+ home.z = local_position.z;
+
+ warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+
+ /* announce new home position */
+ if (home_pub > 0) {
+ orb_publish(ORB_ID(home_position), home_pub, &home);
+
+ } else {
+ home_pub = orb_advertise(ORB_ID(home_position), &home);
+ }
+
+ /* mark home position as set */
+ status.condition_home_position_valid = true;
+ tune_positive(true);
+ }
+
/* update condition_local_position_valid and condition_local_altitude_valid */
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid, &(status.condition_local_position_valid), &status_changed);
+ /* hysteresis for EPH */
+ bool local_eph_good;
+
+ if (status.condition_global_position_valid) {
+ if (local_position.eph > eph_epv_threshold * 2.0f) {
+ local_eph_good = false;
+
+ } else {
+ local_eph_good = true;
+ }
+
+ } else {
+ if (local_position.eph < eph_epv_threshold) {
+ local_eph_good = true;
+
+ } else {
+ local_eph_good = false;
+ }
+ }
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
- if (status.is_rotary_wing && status.condition_local_altitude_valid) {
+ if (status.condition_local_altitude_valid) {
if (status.condition_landed != local_position.landed) {
status.condition_landed = local_position.landed;
status_changed = true;
if (status.condition_landed) {
- mavlink_log_critical(mavlink_fd, "#audio: LANDED");
+ mavlink_log_critical(mavlink_fd, "LANDED MODE");
} else {
- mavlink_log_critical(mavlink_fd, "#audio: IN AIR");
+ mavlink_log_critical(mavlink_fd, "IN AIR MODE");
}
}
}
@@ -921,6 +1199,7 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
+
/* only consider battery voltage if system has been running 2s and battery voltage is valid */
if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
status.battery_voltage = battery.voltage_filtered_v;
@@ -965,12 +1244,20 @@ int commander_thread_main(int argc, char *argv[])
status_changed = true;
}
+ /* update position setpoint triplet */
+ orb_check(pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), pos_sp_triplet_sub, &pos_sp_triplet);
+ }
+
if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
/* compute system load */
uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
- if (last_idle_time > 0)
- status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ if (last_idle_time > 0) {
+ status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ }
last_idle_time = system_load.tasks[0].total_runtime;
@@ -982,25 +1269,30 @@ int commander_thread_main(int argc, char *argv[])
/* if battery voltage is getting lower, warn using buzzer, etc. */
if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) {
low_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY");
+ mavlink_log_critical(mavlink_fd, "LOW BATTERY, RETURN TO LAND ADVISED");
status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
status_changed = true;
- battery_tune_played = false;
} else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) {
/* critical battery voltage, this is rather an emergency, change state machine */
critical_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY");
+ mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY");
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
- battery_tune_played = false;
if (armed.armed) {
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED_ERROR, &armed);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd);
+
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
} else {
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY_ERROR, &armed);
- }
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
+ }
status_changed = true;
}
@@ -1008,11 +1300,15 @@ int commander_thread_main(int argc, char *argv[])
/* If in INIT state, try to proceed to STANDBY state */
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
- // XXX check for sensors
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ /* TODO: check for sensors */
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
+
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
} else {
- // XXX: Add emergency stuff if sensors are lost
+ /* TODO: Add emergency stuff if sensors are lost */
}
@@ -1029,163 +1325,152 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
- /* check if GPS fix is ok */
- float hdop_threshold_m = 4.0f;
- float vdop_threshold_m = 8.0f;
-
- /*
- * If horizontal dilution of precision (hdop / eph)
- * and vertical diluation of precision (vdop / epv)
- * are below a certain threshold (e.g. 4 m), AND
- * home position is not yet set AND the last GPS
- * GPS measurement is not older than two seconds AND
- * the system is currently not armed, set home
- * position to the current position.
- */
-
- if (!home_position_set && gps_position.fix_type >= 3 &&
- (gps_position.eph_m < hdop_threshold_m) && (gps_position.epv_m < vdop_threshold_m) && // XXX note that vdop is 0 for mtk
- (hrt_absolute_time() < gps_position.timestamp_position + POSITION_TIMEOUT) && !armed.armed) {
- /* copy position data to uORB home message, store it locally as well */
- // TODO use global position estimate
- home.lat = gps_position.lat;
- home.lon = gps_position.lon;
- home.alt = gps_position.alt;
-
- home.eph_m = gps_position.eph_m;
- home.epv_m = gps_position.epv_m;
-
- home.s_variance_m_s = gps_position.s_variance_m_s;
- home.p_variance_m = gps_position.p_variance_m;
-
- double home_lat_d = home.lat * 1e-7;
- double home_lon_d = home.lon * 1e-7;
- warnx("home: lat = %.7f, lon = %.7f", home_lat_d, home_lon_d);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f", home_lat_d, home_lon_d);
-
- /* announce new home position */
- if (home_pub > 0) {
- orb_publish(ORB_ID(home_position), home_pub, &home);
+ }
- } else {
- home_pub = orb_advertise(ORB_ID(home_position), &home);
- }
+ orb_check(mission_result_sub, &updated);
- /* mark home position as set */
- home_position_set = true;
- tune_positive();
- }
+ if (updated) {
+ orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
}
- /* ignore RC signals if in offboard control mode */
- if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0 && !status.rc_input_blocked) {
- /* start RC input check */
- if (hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
- /* handle the case where RC signal was regained */
- if (!status.rc_signal_found_once) {
- status.rc_signal_found_once = true;
- mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time");
- status_changed = true;
+ /* RC input check */
+ if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
+ /* handle the case where RC signal was regained */
+ if (!status.rc_signal_found_once) {
+ status.rc_signal_found_once = true;
+ mavlink_log_critical(mavlink_fd, "detected RC signal first time");
+ status_changed = true;
- } else {
- if (status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: RC signal regained");
- status_changed = true;
- }
+ } else {
+ if (status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "RC signal regained");
+ status_changed = true;
}
+ }
- status.rc_signal_lost = false;
-
- transition_result_t res; // store all transitions results here
-
- /* arm/disarm by RC */
- res = TRANSITION_NOT_CHANGED;
-
- /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm
- * do it only for rotary wings */
- if (status.is_rotary_wing &&
- (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.navigation_state == NAVIGATION_STATE_AUTO_READY ||
- (status.condition_landed && (
- status.navigation_state == NAVIGATION_STATE_ALTHOLD ||
- status.navigation_state == NAVIGATION_STATE_VECTOR
- ))) && sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
- if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
- arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- res = arming_state_transition(&status, &safety, &control_mode, new_arming_state, &armed);
- stick_off_counter = 0;
-
- } else {
- stick_off_counter++;
+ status.rc_signal_lost = false;
+
+ /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSIST mode and landed) -> disarm
+ * do it only for rotary wings */
+ if (status.is_rotary_wing &&
+ (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
+ (status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
+ sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
+
+ if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
+ /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
+ arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+ arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
}
+ stick_off_counter = 0;
} else {
- stick_off_counter = 0;
+ stick_off_counter++;
}
- /* check if left stick is in lower right position and we're in MANUAL mode -> arm */
- if (status.arming_state == ARMING_STATE_STANDBY &&
- sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
- if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- if (safety.safety_switch_available && !safety.safety_off) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
-
- } else if (status.main_state != MAIN_STATE_MANUAL) {
- print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
-
- } else {
- res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
- }
-
- stick_on_counter = 0;
+ } else {
+ stick_off_counter = 0;
+ }
+ /* check if left stick is in lower right position and we're in MANUAL mode -> arm */
+ if (status.arming_state == ARMING_STATE_STANDBY &&
+ sp_man.r > STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
+ if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
+
+ /* we check outside of the transition function here because the requirement
+ * for being in manual mode only applies to manual arming actions.
+ * the system can be armed in auto if armed via the GCS.
+ */
+ if (status.main_state != MAIN_STATE_MANUAL) {
+ print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
} else {
- stick_on_counter++;
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
}
- } else {
stick_on_counter = 0;
+
+ } else {
+ stick_on_counter++;
}
- if (res == TRANSITION_CHANGED) {
- if (status.arming_state == ARMING_STATE_ARMED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
+ } else {
+ stick_on_counter = 0;
+ }
- } else {
- mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
- }
+ if (arming_ret == TRANSITION_CHANGED) {
+ if (status.arming_state == ARMING_STATE_ARMED) {
+ mavlink_log_info(mavlink_fd, "ARMED by RC");
- } else if (res == TRANSITION_DENIED) {
- warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
- mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ } else {
+ mavlink_log_info(mavlink_fd, "DISARMED by RC");
}
+ arming_state_changed = true;
+
+ } else if (arming_ret == TRANSITION_DENIED) {
+ /* DENIED here indicates bug in the commander */
+ mavlink_log_critical(mavlink_fd, "arming state transition denied");
+ tune_negative(true);
+ }
- /* fill current_status according to mode switches */
- check_mode_switches(&sp_man, &status);
+ /* evaluate the main state machine according to mode switches */
+ transition_result_t main_res = set_main_state_rc(&status, &sp_man);
- /* evaluate the main state machine */
- res = check_main_state_machine(&status);
+ /* play tune on mode change only if armed, blink LED always */
+ if (main_res == TRANSITION_CHANGED) {
+ tune_positive(armed.armed);
+ main_state_changed = true;
- if (res == TRANSITION_CHANGED) {
- //mavlink_log_info(mavlink_fd, "[cmd] main state: %d", status.main_state);
- tune_positive();
+ } else if (main_res == TRANSITION_DENIED) {
+ /* DENIED here indicates bug in the commander */
+ mavlink_log_critical(mavlink_fd, "main state transition denied");
+ }
- } else if (res == TRANSITION_DENIED) {
- /* DENIED here indicates bug in the commander */
- warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
- mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ } else {
+ if (!status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST");
+ status.rc_signal_lost = true;
+ status_changed = true;
+ }
+ }
+
+ /* data links check */
+ bool have_link = false;
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
+ /* handle the case where data link was regained */
+ if (telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "data link %i regained", i);
+ telemetry_lost[i] = false;
}
+ have_link = true;
} else {
- if (!status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST");
- status.rc_signal_lost = true;
- status_changed = true;
+ if (!telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "data link %i lost", i);
+ telemetry_lost[i] = true;
}
}
}
+ if (have_link) {
+ /* handle the case where data link was regained */
+ if (status.data_link_lost) {
+ status.data_link_lost = false;
+ status_changed = true;
+ }
+
+ } else {
+ if (!status.data_link_lost) {
+ mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST");
+ status.data_link_lost = true;
+ status_changed = true;
+ }
+ }
/* handle commands last, as the system needs to be updated to handle them */
orb_check(cmd_sub, &updated);
@@ -1195,40 +1480,83 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- handle_command(&status, &safety, &control_mode, &cmd, &armed);
+ if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub)) {
+ status_changed = true;
+ }
}
- /* evaluate the navigation state machine */
- transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
+ hrt_abstime t1 = hrt_absolute_time();
- if (res == TRANSITION_DENIED) {
- /* DENIED here indicates bug in the commander */
- warnx("ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
- mavlink_log_critical(mavlink_fd, "#audio: ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
+ /* print new state */
+ if (arming_state_changed) {
+ status_changed = true;
+ mavlink_log_info(mavlink_fd, "[cmd] arming state: %s", arming_states_str[status.arming_state]);
+
+ /* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
+ if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+
+ // TODO remove code duplication
+ home.lat = global_position.lat;
+ home.lon = global_position.lon;
+ home.alt = global_position.alt;
+
+ home.x = local_position.x;
+ home.y = local_position.y;
+ home.z = local_position.z;
+
+ warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+
+ /* announce new home position */
+ if (home_pub > 0) {
+ orb_publish(ORB_ID(home_position), home_pub, &home);
+
+ } else {
+ home_pub = orb_advertise(ORB_ID(home_position), &home);
+ }
+
+ /* mark home position as set */
+ status.condition_home_position_valid = true;
+ }
+ arming_state_changed = false;
}
- /* check which state machines for changes, clear "changed" flag */
- bool arming_state_changed = check_arming_state_changed();
- bool main_state_changed = check_main_state_changed();
- bool navigation_state_changed = check_navigation_state_changed();
+ was_armed = armed.armed;
- hrt_abstime t1 = hrt_absolute_time();
+ /* now set navigation state according to failsafe and main state */
+ bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled,
+ mission_result.finished);
- if (navigation_state_changed || arming_state_changed) {
- control_mode.flag_armed = armed.armed; // copy armed state to vehicle_control_mode topic
+ // TODO handle mode changes by commands
+ if (main_state_changed) {
+ status_changed = true;
+ warnx("main state: %s", main_states_str[status.main_state]);
+ mavlink_log_info(mavlink_fd, "[cmd] main state: %s", main_states_str[status.main_state]);
+ main_state_changed = false;
+ }
+
+ if (status.failsafe != failsafe_old) {
+ status_changed = true;
+ mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %i", status.failsafe);
+ failsafe_old = status.failsafe;
}
- if (arming_state_changed || main_state_changed || navigation_state_changed) {
- mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
+ if (nav_state_changed) {
status_changed = true;
+ warnx("nav state: %s", nav_states_str[status.nav_state]);
+ mavlink_log_info(mavlink_fd, "[cmd] nav state: %s", nav_states_str[status.nav_state]);
}
/* publish states (armed, control mode, vehicle status) at least with 5 Hz */
if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
- status.timestamp = t1;
- orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+ set_control_mode();
control_mode.timestamp = t1;
orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
+
+ status.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+
armed.timestamp = t1;
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
}
@@ -1236,26 +1564,23 @@ int commander_thread_main(int argc, char *argv[])
/* play arming and battery warning tunes */
if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) {
/* play tune when armed */
- if (tune_arm() == OK)
- arm_tune_played = true;
-
- } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
- /* play tune on battery warning */
- if (tune_low_bat() == OK)
- battery_tune_played = true;
+ set_tune(TONE_ARMING_WARNING_TUNE);
+ arm_tune_played = true;
} else if (status.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* play tune on battery critical */
- if (tune_critical_bat() == OK)
- battery_tune_played = true;
+ set_tune(TONE_BATTERY_WARNING_FAST_TUNE);
- } else if (battery_tune_played) {
- tune_stop();
- battery_tune_played = false;
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe) {
+ /* play tune on battery warning or failsafe */
+ set_tune(TONE_BATTERY_WARNING_SLOW_TUNE);
+
+ } else {
+ set_tune(TONE_STOP_TUNE);
}
/* reset arm_tune_played when disarmed */
- if (status.arming_state != ARMING_STATE_ARMED || (safety.safety_switch_available && !safety.safety_off)) {
+ if (!armed.armed || (safety.safety_switch_available && !safety.safety_off)) {
arm_tune_played = false;
}
@@ -1305,6 +1630,7 @@ int commander_thread_main(int argc, char *argv[])
close(diff_pres_sub);
close(param_changed_sub);
close(battery_sub);
+ close(mission_pub);
thread_running = false;
@@ -1324,22 +1650,22 @@ check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *val
}
void
-control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed)
+control_status_leds(vehicle_status_s *status_local, const actuator_armed_s *actuator_armed, bool changed)
{
/* driving rgbled */
if (changed) {
bool set_normal_color = false;
/* set mode */
- if (status->arming_state == ARMING_STATE_ARMED) {
+ if (status_local->arming_state == ARMING_STATE_ARMED) {
rgbled_set_mode(RGBLED_MODE_ON);
set_normal_color = true;
- } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ } else if (status_local->arming_state == ARMING_STATE_ARMED_ERROR) {
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
rgbled_set_color(RGBLED_COLOR_RED);
- } else if (status->arming_state == ARMING_STATE_STANDBY) {
+ } else if (status_local->arming_state == ARMING_STATE_STANDBY) {
rgbled_set_mode(RGBLED_MODE_BREATHE);
set_normal_color = true;
@@ -1350,15 +1676,12 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
if (set_normal_color) {
/* set color */
- if (status->battery_warning != VEHICLE_BATTERY_WARNING_NONE) {
- if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
- rgbled_set_color(RGBLED_COLOR_AMBER);
- }
-
+ if (status_local->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status_local->failsafe) {
+ rgbled_set_color(RGBLED_COLOR_AMBER);
/* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
} else {
- if (status->condition_local_position_valid) {
+ if (status_local->condition_local_position_valid) {
rgbled_set_color(RGBLED_COLOR_GREEN);
} else {
@@ -1377,21 +1700,24 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
} else if (actuator_armed->ready_to_arm) {
/* ready to arm, blink at 1Hz */
- if (leds_counter % 20 == 0)
+ if (leds_counter % 20 == 0) {
led_toggle(LED_BLUE);
+ }
} else {
/* not ready to arm, blink at 10Hz */
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_BLUE);
+ }
}
#endif
/* give system warnings on error LED, XXX maybe add memory usage warning too */
- if (status->load > 0.95f) {
- if (leds_counter % 2 == 0)
+ if (status_local->load > 0.95f) {
+ if (leds_counter % 2 == 0) {
led_toggle(LED_AMBER);
+ }
} else {
led_off(LED_AMBER);
@@ -1400,109 +1726,125 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
leds_counter++;
}
-void
-check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *current_status)
+transition_result_t
+set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_setpoint_s *sp_man)
{
- /* main mode switch */
- if (!isfinite(sp_man->mode_switch)) {
- /* default to manual if signal is invalid */
- current_status->mode_switch = MODE_SWITCH_MANUAL;
-
- } else if (sp_man->mode_switch > STICK_ON_OFF_LIMIT) {
- current_status->mode_switch = MODE_SWITCH_AUTO;
+ /* set main state according to RC switches */
+ transition_result_t res = TRANSITION_DENIED;
- } else if (sp_man->mode_switch < -STICK_ON_OFF_LIMIT) {
- current_status->mode_switch = MODE_SWITCH_MANUAL;
+ /* offboard switch overrides main switch */
+ if (sp_man->offboard_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+ if (res == TRANSITION_DENIED) {
+ print_reject_mode(status_local, "OFFBOARD");
- } else {
- current_status->mode_switch = MODE_SWITCH_ASSISTED;
+ } else {
+ return res;
+ }
}
- /* land switch */
- if (!isfinite(sp_man->return_switch)) {
- current_status->return_switch = RETURN_SWITCH_NONE;
-
- } else if (sp_man->return_switch > STICK_ON_OFF_LIMIT) {
- current_status->return_switch = RETURN_SWITCH_RETURN;
+ /* offboard switched off or denied, check main mode switch */
+ switch (sp_man->mode_switch) {
+ case SWITCH_POS_NONE:
+ res = TRANSITION_NOT_CHANGED;
+ break;
- } else {
- current_status->return_switch = RETURN_SWITCH_NONE;
- }
+ case SWITCH_POS_OFF: // MANUAL
+ if (sp_man->acro_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_ACRO);
- /* assisted switch */
- if (!isfinite(sp_man->assisted_switch)) {
- current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
+ } else {
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
+ }
+ // TRANSITION_DENIED is not possible here
+ break;
- } else if (sp_man->assisted_switch > STICK_ON_OFF_LIMIT) {
- current_status->assisted_switch = ASSISTED_SWITCH_EASY;
+ case SWITCH_POS_MIDDLE: // ASSIST
+ if (sp_man->posctl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_POSCTL);
- } else {
- current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
- }
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
- /* mission switch */
- if (!isfinite(sp_man->mission_switch)) {
- current_status->mission_switch = MISSION_SWITCH_MISSION;
+ print_reject_mode(status_local, "POSCTL");
+ }
- } else if (sp_man->mission_switch > STICK_ON_OFF_LIMIT) {
- current_status->mission_switch = MISSION_SWITCH_NONE;
+ // fallback to ALTCTL
+ res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
- } else {
- current_status->mission_switch = MISSION_SWITCH_MISSION;
- }
-}
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this mode
+ }
-transition_result_t
-check_main_state_machine(struct vehicle_status_s *current_status)
-{
- /* evaluate the main state machine */
- transition_result_t res = TRANSITION_DENIED;
+ if (sp_man->posctl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status_local, "ALTCTL");
+ }
- switch (current_status->mode_switch) {
- case MODE_SWITCH_MANUAL:
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // fallback to MANUAL
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
// TRANSITION_DENIED is not possible here
break;
- case MODE_SWITCH_ASSISTED:
- if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) {
- res = main_state_transition(current_status, MAIN_STATE_EASY);
+ case SWITCH_POS_ON: // AUTO
+ if (sp_man->return_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_RTL);
- if (res != TRANSITION_DENIED)
+ if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
+ }
- // else fallback to SEATBELT
- print_reject_mode(current_status, "EASY");
- }
+ print_reject_mode(status_local, "AUTO_RTL");
- res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this mode
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
- if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
- print_reject_mode(current_status, "SEATBELT");
+ } else if (sp_man->loiter_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
- // else fallback to MANUAL
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
- // TRANSITION_DENIED is not possible here
- break;
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
- case MODE_SWITCH_AUTO:
- res = main_state_transition(current_status, MAIN_STATE_AUTO);
+ print_reject_mode(status_local, "AUTO_LOITER");
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this state
+ } else {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ print_reject_mode(status_local, "AUTO_MISSION");
+
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+ }
+
+ // fallback to POSCTL
+ res = main_state_transition(status_local, MAIN_STATE_POSCTL);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
- // else fallback to SEATBELT (EASY likely will not work too)
- print_reject_mode(current_status, "AUTO");
- res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+ // fallback to ALTCTL
+ res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
- if (res != TRANSITION_DENIED)
+ if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
+ }
- // else fallback to MANUAL
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // fallback to MANUAL
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
// TRANSITION_DENIED is not possible here
break;
@@ -1514,194 +1856,211 @@ check_main_state_machine(struct vehicle_status_s *current_status)
}
void
-print_reject_mode(struct vehicle_status_s *current_status, const char *msg)
+set_control_mode()
{
- hrt_abstime t = hrt_absolute_time();
+ /* set vehicle_control_mode according to set_navigation_state */
+ control_mode.flag_armed = armed.armed;
+ /* TODO: check this */
+ control_mode.flag_external_manual_override_ok = !status.is_rotary_wing;
+ control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON;
+ control_mode.flag_control_offboard_enabled = false;
- if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
- last_print_mode_reject_time = t;
- char s[80];
- sprintf(s, "#audio: REJECT %s", msg);
- mavlink_log_critical(mavlink_fd, s);
-
- // only buzz if armed, because else we're driving people nuts indoors
- // they really need to look at the leds as well.
- if (current_status->arming_state == ARMING_STATE_ARMED) {
- tune_negative();
- } else {
+ switch (status.nav_state) {
+ case NAVIGATION_STATE_MANUAL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = status.is_rotary_wing;
+ control_mode.flag_control_attitude_enabled = status.is_rotary_wing;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
- // Always show the led indication
- led_negative();
+ case NAVIGATION_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_ALTCTL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_OFFBOARD:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_offboard_enabled = true;
+
+ switch (sp_offboard.mode) {
+ case OFFBOARD_CONTROL_MODE_DIRECT_RATES:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_velocity_enabled = true;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ break;
+ default:
+ control_mode.flag_control_rates_enabled = false;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
}
+ break;
+
+ case NAVIGATION_STATE_POSCTL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_AUTO_MISSION:
+ case NAVIGATION_STATE_AUTO_LOITER:
+ case NAVIGATION_STATE_AUTO_RTL:
+ case NAVIGATION_STATE_AUTO_RTGS:
+ control_mode.flag_control_manual_enabled = false;
+ 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_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_LAND:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = true;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_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;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_TERMINATION:
+ /* disable all controllers on termination */
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = false;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_termination_enabled = true;
+ break;
+
+ default:
+ break;
}
}
void
-print_reject_arm(const char *msg)
+print_reject_mode(struct vehicle_status_s *status_local, const char *msg)
{
hrt_abstime t = hrt_absolute_time();
if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
last_print_mode_reject_time = t;
- char s[80];
- sprintf(s, "#audio: %s", msg);
- mavlink_log_critical(mavlink_fd, s);
- tune_negative();
+ mavlink_log_critical(mavlink_fd, "REJECT %s", msg);
+
+ /* only buzz if armed, because else we're driving people nuts indoors
+ they really need to look at the leds as well. */
+ tune_negative(armed.armed);
}
}
-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)
+void
+print_reject_arm(const char *msg)
{
- transition_result_t res = TRANSITION_DENIED;
-
- if (status->main_state == MAIN_STATE_AUTO) {
- if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
- // TODO AUTO_LAND handling
- if (status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
- /* don't switch to other states until takeoff not completed */
- // XXX: only respect the condition_landed when the local position is actually valid
- if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
- return TRANSITION_NOT_CHANGED;
- }
- }
-
- if (status->navigation_state != NAVIGATION_STATE_AUTO_TAKEOFF &&
- status->navigation_state != NAVIGATION_STATE_AUTO_LOITER &&
- status->navigation_state != NAVIGATION_STATE_AUTO_MISSION &&
- status->navigation_state != NAVIGATION_STATE_AUTO_RTL) {
- /* possibly on ground, switch to TAKEOFF if needed */
- if (status->is_rotary_wing && status->condition_local_altitude_valid && (local_pos->z > -takeoff_alt || status->condition_landed)) {
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
- return res;
- }
- }
-
- /* switch to AUTO mode */
- if (status->rc_signal_found_once && !status->rc_signal_lost) {
- /* act depending on switches when manual control enabled */
- if (status->return_switch == RETURN_SWITCH_RETURN) {
- /* RTL */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_RTL, control_mode);
-
- } else {
- if (status->mission_switch == MISSION_SWITCH_MISSION) {
- /* MISSION */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
-
- } else {
- /* LOITER */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_LOITER, control_mode);
- }
- }
-
- } else {
- /* switch to MISSION when no RC control and first time in some AUTO mode */
- if (status->navigation_state == NAVIGATION_STATE_AUTO_LOITER ||
- status->navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
- status->navigation_state == NAVIGATION_STATE_AUTO_RTL ||
- status->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
- res = TRANSITION_NOT_CHANGED;
-
- } else {
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
- }
- }
-
- } else {
- /* disarmed, always switch to AUTO_READY */
- res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode);
- }
-
- } else {
- /* manual control modes */
- if (status->rc_signal_lost && (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR)) {
- /* switch to failsafe mode */
- bool manual_control_old = control_mode->flag_control_manual_enabled;
-
- if (!status->condition_landed && status->condition_local_position_valid) {
- /* in air: try to hold position if possible */
- res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
-
- } else {
- /* landed: don't try to hold position but land (if taking off) */
- res = TRANSITION_DENIED;
- }
-
- if (res == TRANSITION_DENIED) {
- res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
- }
-
- control_mode->flag_control_manual_enabled = false;
-
- if (res == TRANSITION_NOT_CHANGED && manual_control_old) {
- /* mark navigation state as changed to force immediate flag publishing */
- set_navigation_state_changed();
- res = TRANSITION_CHANGED;
- }
-
- if (res == TRANSITION_CHANGED) {
- if (control_mode->flag_control_position_enabled) {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: POS HOLD");
-
- } else {
- if (status->condition_landed) {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD (LAND)");
-
- } else {
- mavlink_log_critical(mavlink_fd, "#audio: FAILSAFE: ALT HOLD");
- }
- }
- }
-
- } else {
- switch (status->main_state) {
- case MAIN_STATE_MANUAL:
- res = navigation_state_transition(status, status->is_rotary_wing ? NAVIGATION_STATE_STABILIZE : NAVIGATION_STATE_DIRECT, control_mode);
- break;
-
- case MAIN_STATE_SEATBELT:
- res = navigation_state_transition(status, NAVIGATION_STATE_ALTHOLD, control_mode);
- break;
-
- case MAIN_STATE_EASY:
- res = navigation_state_transition(status, NAVIGATION_STATE_VECTOR, control_mode);
- break;
+ hrt_abstime t = hrt_absolute_time();
- default:
- break;
- }
- }
+ if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
+ last_print_mode_reject_time = t;
+ mavlink_log_critical(mavlink_fd, msg);
+ tune_negative(true);
}
-
- return res;
}
void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
- tune_positive();
+ tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
- mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd.command);
- tune_negative();
+ mavlink_log_critical(mavlink_fd, "command denied: %u", cmd.command);
+ tune_negative(true);
break;
case VEHICLE_CMD_RESULT_FAILED:
- mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd.command);
- tune_negative();
+ mavlink_log_critical(mavlink_fd, "command failed: %u", cmd.command);
+ tune_negative(true);
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command);
- tune_negative();
+ /* this needs additional hints to the user - so let other messages pass and be spoken */
+ mavlink_log_critical(mavlink_fd, "command temporarily rejected: %u", cmd.command);
+ tune_negative(true);
break;
case VEHICLE_CMD_RESULT_UNSUPPORTED:
- mavlink_log_critical(mavlink_fd, "#audio: command unsupported: %u", cmd.command);
- tune_negative();
+ mavlink_log_critical(mavlink_fd, "command unsupported: %u", cmd.command);
+ tune_negative(true);
break;
default:
@@ -1731,8 +2090,9 @@ void *commander_low_prio_loop(void *arg)
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
/* timed out - periodic check for thread_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1746,8 +2106,10 @@ void *commander_low_prio_loop(void *arg)
/* ignore commands the high-prio loop handles */
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
- cmd.command == VEHICLE_CMD_NAV_TAKEOFF)
+ cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
+ cmd.command == VEHICLE_CMD_DO_SET_SERVO) {
continue;
+ }
/* only handle low-priority commands here */
switch (cmd.command) {
@@ -1782,9 +2144,7 @@ void *commander_low_prio_loop(void *arg)
int calib_ret = ERROR;
/* try to go to INIT/PREFLIGHT arming state */
-
- // XXX disable interrupts in arming_state_transition
- if (TRANSITION_DENIED == arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_INIT, &armed)) {
+ if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
break;
}
@@ -1825,6 +2185,7 @@ void *commander_low_prio_loop(void *arg)
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
@@ -1839,12 +2200,14 @@ void *commander_low_prio_loop(void *arg)
}
- if (calib_ret == OK)
- tune_positive();
- else
- tune_negative();
+ if (calib_ret == OK) {
+ tune_positive(true);
+
+ } else {
+ tune_negative(true);
+ }
- arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
break;
}
@@ -1862,11 +2225,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters load ERROR");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1882,11 +2247,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters save error");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1896,11 +2263,11 @@ void *commander_low_prio_loop(void *arg)
}
case VEHICLE_CMD_START_RX_PAIR:
- /* handled in the IO driver */
- break;
+ /* handled in the IO driver */
+ break;
default:
- answer_command(cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
+ /* don't answer on unsupported commands, it will be done in main loop */
break;
}
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 033e7dc88..d5fe122cb 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Anton Babushkin <anton.babushkin@me.com>
+ * 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
@@ -37,6 +34,11 @@
/**
* @file commander_helper.cpp
* Commander helper functions implementations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
*/
#include <stdio.h>
@@ -45,6 +47,7 @@
#include <stdbool.h>
#include <fcntl.h>
#include <math.h>
+#include <string.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
@@ -81,11 +84,22 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status)
|| (current_status->system_type == VEHICLE_TYPE_COAXIAL);
}
-static int buzzer;
-static hrt_abstime blink_msg_end;
+static int buzzer = -1;
+static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message
+static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence
+static int tune_current = TONE_STOP_TUNE; // currently playing tune, can be interrupted after tune_end
+static unsigned int tune_durations[TONE_NUMBER_OF_TUNES];
int buzzer_init()
{
+ tune_end = 0;
+ tune_current = 0;
+ memset(tune_durations, 0, sizeof(tune_durations));
+ tune_durations[TONE_NOTIFY_POSITIVE_TUNE] = 800000;
+ tune_durations[TONE_NOTIFY_NEGATIVE_TUNE] = 900000;
+ tune_durations[TONE_NOTIFY_NEUTRAL_TUNE] = 500000;
+ tune_durations[TONE_ARMING_WARNING_TUNE] = 3000000;
+
buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY);
if (buzzer < 0) {
@@ -101,58 +115,68 @@ void buzzer_deinit()
close(buzzer);
}
-void tune_error()
+void set_tune(int tune)
{
- ioctl(buzzer, TONE_SET_ALARM, TONE_ERROR_TUNE);
+ unsigned int new_tune_duration = tune_durations[tune];
+
+ /* don't interrupt currently playing non-repeating tune by repeating */
+ if (tune_end == 0 || new_tune_duration != 0 || hrt_absolute_time() > tune_end) {
+ /* allow interrupting current non-repeating tune by the same tune */
+ if (tune != tune_current || new_tune_duration != 0) {
+ ioctl(buzzer, TONE_SET_ALARM, tune);
+ }
+
+ tune_current = tune;
+
+ if (new_tune_duration != 0) {
+ tune_end = hrt_absolute_time() + new_tune_duration;
+
+ } else {
+ tune_end = 0;
+ }
+ }
}
-void tune_positive()
+/**
+ * Blink green LED and play positive tune (if use_buzzer == true).
+ */
+void tune_positive(bool use_buzzer)
{
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_GREEN);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
- ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_POSITIVE_TUNE);
+
+ if (use_buzzer) {
+ set_tune(TONE_NOTIFY_POSITIVE_TUNE);
+ }
}
-void tune_neutral()
+/**
+ * Blink white LED and play neutral tune (if use_buzzer == true).
+ */
+void tune_neutral(bool use_buzzer)
{
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_WHITE);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
- ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEUTRAL_TUNE);
-}
-void tune_negative()
-{
- led_negative();
- ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
+ if (use_buzzer) {
+ set_tune(TONE_NOTIFY_NEUTRAL_TUNE);
+ }
}
-void led_negative()
+/**
+ * Blink red LED and play negative tune (if use_buzzer == true).
+ */
+void tune_negative(bool use_buzzer)
{
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_RED);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
-}
-
-int tune_arm()
-{
- return ioctl(buzzer, TONE_SET_ALARM, TONE_ARMING_WARNING_TUNE);
-}
-
-int tune_low_bat()
-{
- return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_SLOW_TUNE);
-}
-int tune_critical_bat()
-{
- return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_FAST_TUNE);
-}
-
-void tune_stop()
-{
- ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE);
+ if (use_buzzer) {
+ set_tune(TONE_NOTIFY_NEGATIVE_TUNE);
+ }
}
int blink_msg_state()
@@ -161,6 +185,7 @@ int blink_msg_state()
return 0;
} else if (hrt_absolute_time() > blink_msg_end) {
+ blink_msg_end = 0;
return 2;
} else {
@@ -168,8 +193,8 @@ int blink_msg_state()
}
}
-static int leds;
-static int rgbleds;
+static int leds = -1;
+static int rgbleds = -1;
int led_init()
{
@@ -183,30 +208,26 @@ int led_init()
return ERROR;
}
- /* the blue LED is only available on FMUv1 but not FMUv2 */
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
-
- if (ioctl(leds, LED_ON, LED_BLUE)) {
- warnx("Blue LED: ioctl fail\n");
- return ERROR;
- }
+ /* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
+ (void)ioctl(leds, LED_ON, LED_BLUE);
-#endif
+ /* switch blue off */
+ led_off(LED_BLUE);
+ /* we consider the amber led mandatory */
if (ioctl(leds, LED_ON, LED_AMBER)) {
warnx("Amber LED: ioctl fail\n");
return ERROR;
}
+ /* switch amber off */
+ led_off(LED_AMBER);
+
/* then try RGB LEDs, this can fail on FMUv1*/
rgbleds = open(RGBLED_DEVICE_PATH, 0);
if (rgbleds == -1) {
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
- errx(1, "Unable to open " RGBLED_DEVICE_PATH);
-#else
- warnx("No RGB LED found");
-#endif
+ warnx("No RGB LED found at " RGBLED_DEVICE_PATH);
}
return 0;
@@ -239,22 +260,25 @@ int led_off(int led)
void rgbled_set_color(rgbled_color_t color)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+ }
}
void rgbled_set_mode(rgbled_mode_t mode)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+ }
}
void rgbled_set_pattern(rgbled_pattern_t *pattern)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+ }
}
float battery_remaining_estimate_voltage(float voltage, float discharged)
@@ -294,6 +318,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged)
if (bat_capacity > 0.0f) {
/* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
+
} else {
/* else use voltage */
ret = remaining_voltage;
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
index af25a5e97..a49c9e263 100644
--- a/src/modules/commander/commander_helper.h
+++ b/src/modules/commander/commander_helper.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.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
@@ -36,6 +34,9 @@
/**
* @file commander_helper.h
* Commander helper functions definitions
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#ifndef COMMANDER_HELPER_H_
@@ -54,16 +55,10 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status);
int buzzer_init(void);
void buzzer_deinit(void);
-void tune_error(void);
-void tune_positive(void);
-void tune_neutral(void);
-void tune_negative(void);
-int tune_arm(void);
-int tune_low_bat(void);
-int tune_critical_bat(void);
-void tune_stop(void);
-
-void led_negative();
+void set_tune(int tune);
+void tune_positive(bool use_buzzer);
+void tune_neutral(bool use_buzzer);
+void tune_negative(bool use_buzzer);
int blink_msg_state();
@@ -83,6 +78,8 @@ void rgbled_set_pattern(rgbled_pattern_t *pattern);
* Use integral of current if battery capacity known (BAT_CAPACITY parameter set),
* else use simple estimate based on voltage.
*
+ * @param voltage the current battery voltage
+ * @param discharged the discharged capacity
* @return the estimated remaining capacity in 0..1
*/
float battery_remaining_estimate_voltage(float voltage, float discharged);
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index e10b7f18d..4750f9d5c 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -39,18 +39,59 @@
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
-PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 5.0f);
-PARAM_DEFINE_FLOAT(NAV_TAKEOFF_GAP, 3.0f);
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
+
+/**
+ * Empty cell voltage.
+ *
+ * Defines the voltage where a single cell of the battery is considered empty.
+ *
+ * @group Battery Calibration
+ */
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f);
+
+/**
+ * Full cell voltage.
+ *
+ * Defines the voltage where a single cell of the battery is considered full.
+ *
+ * @group Battery Calibration
+ */
PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f);
+
+/**
+ * Number of cells.
+ *
+ * Defines the number of cells the attached battery consists of.
+ *
+ * @group Battery Calibration
+ */
PARAM_DEFINE_INT32(BAT_N_CELLS, 3);
+
+/**
+ * Battery capacity.
+ *
+ * Defines the capacity of the attached battery.
+ *
+ * @group Battery Calibration
+ */
PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
+
+/**
+ * Datalink loss mode enabled.
+ *
+ * Set to 1 to enable actions triggered when the datalink is lost.
+ *
+ * @group commander
+ * @min 0
+ * @max 1
+ */
+PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
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..2e18c4284 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,132 +63,393 @@ 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: standby to armed, 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: standby to armed, 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, 0 /* no mavlink_fd */);
+
+ // 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;
+ // This structure represent a single test case for testing Main State transitions.
+ typedef struct {
+ const char* assertMsg; // Text to show when test case fails
+ uint8_t condition_bits; // Bits for various condition_* values
+ main_state_t from_state; // State prior to transition request
+ main_state_t to_state; // State to transition to
+ transition_result_t expected_transition_result; // Expected result from main_state_transition call
+ } MainTransitionTest_t;
+
+ // Bits for condition_bits
+ #define MTT_ALL_NOT_VALID 0
+ #define MTT_ROTARY_WING 1 << 0
+ #define MTT_LOC_ALT_VALID 1 << 1
+ #define MTT_LOC_POS_VALID 1 << 2
+ #define MTT_HOME_POS_VALID 1 << 3
+ #define MTT_GLOBAL_POS_VALID 1 << 4
- // Identical states.
- current_state.main_state = MAIN_STATE_MANUAL;
- new_main_state = MAIN_STATE_MANUAL;
- mu_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);
-
- // AUTO to MANUAL.
- current_state.main_state = MAIN_STATE_AUTO;
- new_main_state = MAIN_STATE_MANUAL;
- mu_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);
-
- // 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",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_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",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_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",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_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",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_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",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- mu_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",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- mu_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
-
- return 0;
+ static const MainTransitionTest_t rgMainTransitionTests[] = {
+
+ // TRANSITION_NOT_CHANGED tests
+
+ { "no transition: identical states",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_MANUAL, TRANSITION_NOT_CHANGED },
+
+ // TRANSITION_CHANGED tests
+
+ { "transition: MANUAL to ACRO",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ACRO, TRANSITION_CHANGED },
+
+ { "transition: ACRO to MANUAL",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_ACRO, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_MISSION - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_CHANGED },
+
+ { "transition: AUTO_MISSION to MANUAL - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_AUTO_MISSION, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_LOITER - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_CHANGED },
+
+ { "transition: AUTO_LOITER to MANUAL - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_AUTO_LOITER, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_RTL - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_CHANGED },
+
+ { "transition: AUTO_RTL to MANUAL - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
+ MAIN_STATE_AUTO_RTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - not rotary",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude valid",
+ MTT_ROTARY_WING | MTT_LOC_ALT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - rotary, global position valid, local altitude not valid",
+ MTT_ROTARY_WING | MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: ALTCTL to MANUAL - local altitude valid",
+ MTT_LOC_ALT_VALID,
+ MAIN_STATE_ALTCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to POSCTL - local position not valid, global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to POSCTL - local position valid, global position not valid",
+ MTT_LOC_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED },
+
+ { "transition: POSCTL to MANUAL - local position valid, global position valid",
+ MTT_LOC_POS_VALID,
+ MAIN_STATE_POSCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ // TRANSITION_DENIED tests
+
+ { "no transition: MANUAL to AUTO_MISSION - global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_LOITER - global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position not valid, home position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position not valid, home position valid",
+ MTT_HOME_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position valid, home position not valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude not valid",
+ MTT_ROTARY_WING,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to POSCTL - local position not valid, global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_DENIED },
+ };
+
+ size_t cMainTransitionTests = sizeof(rgMainTransitionTests) / sizeof(rgMainTransitionTests[0]);
+ for (size_t i=0; i<cMainTransitionTests; i++) {
+ const MainTransitionTest_t* test = &rgMainTransitionTests[i];
+
+ // Setup initial machine state
+ struct vehicle_status_s current_state;
+ current_state.main_state = test->from_state;
+ current_state.is_rotary_wing = test->condition_bits & MTT_ROTARY_WING;
+ current_state.condition_local_altitude_valid = test->condition_bits & MTT_LOC_ALT_VALID;
+ current_state.condition_local_position_valid = test->condition_bits & MTT_LOC_POS_VALID;
+ current_state.condition_home_position_valid = test->condition_bits & MTT_HOME_POS_VALID;
+ current_state.condition_global_position_valid = test->condition_bits & MTT_GLOBAL_POS_VALID;
+
+ // Attempt transition
+ transition_result_t result = main_state_transition(&current_state, test->to_state);
+
+ // Validate result of transition
+ ut_assert(test->assertMsg, test->expected_transition_result == result);
+ if (test->expected_transition_result == result) {
+ if (test->expected_transition_result == TRANSITION_CHANGED) {
+ ut_assert(test->assertMsg, test->to_state == current_state.main_state);
+ } else {
+ ut_assert(test->assertMsg, test->from_state == current_state.main_state);
+ }
+ }
+ }
+
+
+ return true;
}
-const char*
-StateMachineHelperTest::is_safe_test()
+bool StateMachineHelperTest::isSafeTest(void)
{
struct vehicle_status_s current_state;
struct safety_s safety;
@@ -199,49 +459,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/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 30cd0d48d..cbc2844c1 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -110,8 +110,9 @@ int do_gyro_calibration(int mavlink_fd)
gyro_scale.z_offset += gyro_report.z;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else {
poll_errcount++;
@@ -163,8 +164,9 @@ int do_gyro_calibration(int mavlink_fd)
/* apply new offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale)) {
warn("WARNING: failed to apply new offsets for gyro");
+ }
close(fd);
@@ -178,9 +180,9 @@ int do_gyro_calibration(int mavlink_fd)
float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+ if (mag_last > M_PI_F) { mag_last -= 2 * M_PI_F; }
- if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
+ if (mag_last < -M_PI_F) { mag_last += 2 * M_PI_F; }
uint64_t last_time = hrt_absolute_time();
@@ -220,15 +222,15 @@ int do_gyro_calibration(int mavlink_fd)
//float mag = -atan2f(magNav(1),magNav(0));
float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2 * M_PI_F;
+ if (mag > M_PI_F) { mag -= 2 * M_PI_F; }
- if (mag < -M_PI_F) mag += 2 * M_PI_F;
+ if (mag < -M_PI_F) { mag += 2 * M_PI_F; }
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2 * M_PI_F;
+ if (diff > M_PI_F) { diff -= 2 * M_PI_F; }
- if (diff < -M_PI_F) diff += 2 * M_PI_F;
+ if (diff < -M_PI_F) { diff += 2 * M_PI_F; }
baseline_integral += diff;
mag_last = mag;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 4ebf266f4..0ead22f77 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_interval = 45 * 1000 * 1000;
/* maximum 500 values */
- const unsigned int calibration_maxcount = 500;
+ const unsigned int calibration_maxcount = 240;
unsigned int calibration_counter;
struct mag_scale mscale_null = {
@@ -121,9 +121,24 @@ int do_mag_calibration(int mavlink_fd)
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+
+ /* clean up */
+ if (x != NULL) {
+ free(x);
+ }
+
+ if (y != NULL) {
+ free(y);
+ }
+
+ if (z != NULL) {
+ free(z);
+ }
+
res = ERROR;
return res;
}
+
} else {
/* exit */
return ERROR;
@@ -163,8 +178,9 @@ int do_mag_calibration(int mavlink_fd)
calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
+ if (calibration_counter % (calibration_maxcount / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ }
} else {
poll_errcount++;
@@ -198,14 +214,17 @@ int do_mag_calibration(int mavlink_fd)
}
}
- if (x != NULL)
+ if (x != NULL) {
free(x);
+ }
- if (y != NULL)
+ if (y != NULL) {
free(y);
+ }
- if (z != NULL)
+ if (z != NULL) {
free(z);
+ }
if (res == OK) {
/* apply calibration and set parameters */
@@ -234,23 +253,29 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
/* set parameters */
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
res = ERROR;
+ }
if (res != OK) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
diff --git a/src/modules/commander/mag_calibration.h b/src/modules/commander/mag_calibration.h
index a101cd7b1..c14f948cc 100644
--- a/src/modules/commander/mag_calibration.h
+++ b/src/modules/commander/mag_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. 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
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 554dfcb08..27ca5c182 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,3 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index b60a7e0b9..eaf309288 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -8,11 +8,15 @@
#ifndef PX4_CUSTOM_MODE_H_
#define PX4_CUSTOM_MODE_H_
+#include <stdint.h>
+
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
- PX4_CUSTOM_MAIN_MODE_SEATBELT,
- PX4_CUSTOM_MAIN_MODE_EASY,
+ PX4_CUSTOM_MAIN_MODE_ALTCTL,
+ PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_ACRO,
+ PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
@@ -22,6 +26,7 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
+ PX4_CUSTOM_SUB_MODE_AUTO_RTGS
};
union px4_custom_mode {
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 41f3ca0aa..0776894fb 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -69,11 +69,11 @@ int do_trim_calibration(int mavlink_fd)
orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
/* set parameters */
- float p = sp.roll;
+ float p = sp.y;
param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
+ p = sp.x;
param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
+ p = sp.r;
param_set(param_find("TRIM_YAW"), &p);
/* store to permanent storage */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 7ae61d9ef..372ba9d7d 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.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
@@ -36,6 +34,9 @@
/**
* @file state_machine_helper.cpp
* State machine helper functions implementations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <stdio.h>
@@ -44,15 +45,20 @@
#include <stdbool.h>
#include <dirent.h>
#include <fcntl.h>
+#include <string.h>
+#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_airspeed.h>
#include <drivers/drv_device.h>
#include <mavlink/mavlink_log.h>
@@ -65,134 +71,157 @@
#endif
static const int ERROR = -1;
-static bool arming_state_changed = true;
-static bool main_state_changed = true;
-static bool navigation_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 * const 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,
- const struct vehicle_control_mode_s *control_mode,
- 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
{
- /*
- * Perform an atomic state update
- */
- irqstate_t flags = irqsave();
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
transition_result_t ret = TRANSITION_DENIED;
+ arming_state_t current_arming_state = status->arming_state;
+
/* only check transition if the new state is actually different from the current one */
- if (new_arming_state == status->arming_state) {
+ if (new_arming_state == current_arming_state) {
ret = TRANSITION_NOT_CHANGED;
} else {
+ /*
+ * Get sensing state if necessary
+ */
+ int prearm_ret = OK;
+
+ /* only perform the check if we have to */
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ prearm_ret = prearm_check(status, mavlink_fd);
+ }
+
+ /*
+ * Perform an atomic state update
+ */
+ irqstate_t flags = irqsave();
+
/* enforce lockdown in HIL */
- if (control_mode->flag_system_hil_enabled) {
+ if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
+
} else {
armed->lockdown = false;
}
- switch (new_arming_state) {
- case ARMING_STATE_INIT:
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
- /* 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;
- }
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
- break;
+ // Do not perform pre-arm checks 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) {
- case ARMING_STATE_STANDBY:
+ // Fail transition if pre-arm check fails
+ if (prearm_ret) {
+ valid_transition = false;
- /* allow coming from INIT and disarming from ARMED */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED
- || control_mode->flag_system_hil_enabled) {
+ // Fail transition if we need safety switch press
+ } else if (safety->safety_switch_available && !safety->safety_off) {
- /* 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;
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!");
- 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 || control_mode->flag_system_hil_enabled)) { /* 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;
- }
+ valid_transition = false;
+ }
- break;
+ // Perform power checks only if circuit breaker is not
+ // engaged for these checks
+ if (!status->circuit_breaker_engaged_power_check) {
+ // Fail transition if power is not good
+ if (!status->condition_power_input_valid) {
- case ARMING_STATE_STANDBY_ERROR:
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module.");
+ valid_transition = false;
+ }
- /* 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;
- }
+ // Fail transition if power levels on the avionics rail
+ // are measured but are insufficient
+ if (status->condition_power_input_valid && ((status->avionics_power_rail_voltage > 0.0f) &&
+ (status->avionics_power_rail_voltage < 4.9f))) {
- break;
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
+ valid_transition = false;
+ }
+ }
- 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;
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
}
+ }
- break;
-
- case ARMING_STATE_IN_AIR_RESTORE:
-
- /* XXX implement */
- break;
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
- default:
- break;
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
}
- if (ret == TRANSITION_CHANGED) {
+ // 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);
}
- /* end of atomic state update */
- irqrestore(flags);
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "INVAL: %s - %s";
- if (ret == TRANSITION_DENIED)
- warnx("arming transition rejected");
+ 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;
}
@@ -211,528 +240,448 @@ bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safet
}
}
-bool
-check_arming_state_changed()
-{
- if (arming_state_changed) {
- arming_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
transition_result_t
-main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state)
+main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state)
{
transition_result_t ret = TRANSITION_DENIED;
- /* only check transition if the new state is actually different from the current one */
- if (new_main_state == current_state->main_state) {
- ret = TRANSITION_NOT_CHANGED;
-
- } else {
-
- switch (new_main_state) {
- case MAIN_STATE_MANUAL:
+ /* transition may be denied even if the same state is requested because conditions may have changed */
+ switch (new_main_state) {
+ case MAIN_STATE_MANUAL:
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_ALTCTL:
+ /* need at minimum altitude estimate */
+ /* TODO: add this for fixedwing as well */
+ if (!status->is_rotary_wing ||
+ (status->condition_local_altitude_valid ||
+ status->condition_global_position_valid)) {
ret = TRANSITION_CHANGED;
- break;
-
- case MAIN_STATE_SEATBELT:
-
- /* need at minimum altitude estimate */
- if (current_state->condition_local_altitude_valid ||
- current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
-
- break;
-
- case MAIN_STATE_EASY:
-
- /* need at minimum local position estimate */
- if (current_state->condition_local_position_valid ||
- current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
-
- break;
-
- case MAIN_STATE_AUTO:
-
- /* need global position estimate */
- if (current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
-
- break;
- }
-
- if (ret == TRANSITION_CHANGED) {
- current_state->main_state = new_main_state;
- main_state_changed = true;
}
- }
-
- return ret;
-}
+ break;
-bool
-check_main_state_changed()
-{
- if (main_state_changed) {
- main_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
-transition_result_t
-navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode)
-{
- transition_result_t ret = TRANSITION_DENIED;
-
- /* only check transition if the new state is actually different from the current one */
- if (new_navigation_state == status->navigation_state) {
- ret = TRANSITION_NOT_CHANGED;
-
- } else {
-
- switch (new_navigation_state) {
- case NAVIGATION_STATE_DIRECT:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = false;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_STABILIZE:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_ALTHOLD:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_VECTOR:
+ case MAIN_STATE_POSCTL:
+ /* need at minimum local position estimate */
+ if (status->condition_local_position_valid ||
+ status->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = true;
- control_mode->flag_control_auto_enabled = false;
- break;
-
- case NAVIGATION_STATE_AUTO_READY:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = false;
- control_mode->flag_control_attitude_enabled = false;
- control_mode->flag_control_velocity_enabled = false;
- control_mode->flag_control_position_enabled = false;
- control_mode->flag_control_altitude_enabled = false;
- control_mode->flag_control_climb_rate_enabled = false;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
+ }
+ break;
- case NAVIGATION_STATE_AUTO_TAKEOFF:
+ case MAIN_STATE_AUTO_LOITER:
+ /* need global position estimate */
+ if (status->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
+ }
+ break;
- case NAVIGATION_STATE_AUTO_LOITER:
+ case MAIN_STATE_AUTO_MISSION:
+ case MAIN_STATE_AUTO_RTL:
+ /* need global position and home position */
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = false;
- break;
+ }
+ break;
- case NAVIGATION_STATE_AUTO_MISSION:
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
+ case MAIN_STATE_OFFBOARD:
- case NAVIGATION_STATE_AUTO_RTL:
+ /* need offboard signal */
+ if (!status->offboard_control_signal_lost) {
ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- break;
-
- case NAVIGATION_STATE_AUTO_LAND:
-
- /* deny transitions from landed state */
- if (status->navigation_state != NAVIGATION_STATE_AUTO_READY) {
- ret = TRANSITION_CHANGED;
- control_mode->flag_control_rates_enabled = true;
- control_mode->flag_control_attitude_enabled = true;
- control_mode->flag_control_velocity_enabled = true;
- control_mode->flag_control_position_enabled = true;
- control_mode->flag_control_altitude_enabled = true;
- control_mode->flag_control_climb_rate_enabled = true;
- control_mode->flag_control_manual_enabled = false;
- control_mode->flag_control_auto_enabled = true;
- }
-
- break;
-
- default:
- break;
}
- if (ret == TRANSITION_CHANGED) {
- status->navigation_state = new_navigation_state;
- control_mode->auto_state = status->navigation_state;
- navigation_state_changed = true;
+ break;
+
+ case MAIN_STATE_MAX:
+ default:
+ break;
+ }
+ if (ret == TRANSITION_CHANGED) {
+ if (status->main_state != new_main_state) {
+ status->main_state = new_main_state;
+ } else {
+ ret = TRANSITION_NOT_CHANGED;
}
}
return ret;
}
-bool
-check_navigation_state_changed()
-{
- if (navigation_state_changed) {
- navigation_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
-void
-set_navigation_state_changed()
-{
- navigation_state_changed = true;
-}
-
/**
-* Transition from one hil state to another
-*/
-int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd)
+ * Transition from one hil state to another
+ */
+transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
{
- bool valid_transition = false;
- int ret = ERROR;
-
- warnx("Current state: %d, requested state: %d", current_status->hil_state, new_state);
+ transition_result_t ret = TRANSITION_DENIED;
if (current_status->hil_state == new_state) {
- warnx("Hil state not changed");
- valid_transition = true;
+ ret = TRANSITION_NOT_CHANGED;
} else {
-
switch (new_state) {
-
case HIL_STATE_OFF:
-
/* we're in HIL and unexpected things can happen if we disable HIL now */
- mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
- valid_transition = false;
-
+ mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
+ ret = TRANSITION_DENIED;
break;
case HIL_STATE_ON:
-
if (current_status->arming_state == ARMING_STATE_INIT
|| current_status->arming_state == ARMING_STATE_STANDBY
|| current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- current_control_mode->flag_system_hil_enabled = true;
- mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
- valid_transition = true;
-
- // Disable publication of all attached sensors
-
+ /* Disable publication of all attached sensors */
/* list directory */
DIR *d;
- struct dirent *direntry;
d = opendir("/dev");
+
if (d) {
+ struct dirent *direntry;
+ char devname[24];
while ((direntry = readdir(d)) != NULL) {
- int sensfd = ::open(direntry->d_name, 0);
- int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0);
+ /* skip serial ports */
+ if (!strncmp("tty", direntry->d_name, 3)) {
+ continue;
+ }
+
+ /* skip mtd devices */
+ if (!strncmp("mtd", direntry->d_name, 3)) {
+ continue;
+ }
+
+ /* skip ram devices */
+ if (!strncmp("ram", direntry->d_name, 3)) {
+ continue;
+ }
+
+ /* skip MMC devices */
+ if (!strncmp("mmc", direntry->d_name, 3)) {
+ continue;
+ }
+
+ /* skip mavlink */
+ if (!strcmp("mavlink", direntry->d_name)) {
+ continue;
+ }
+
+ /* skip console */
+ if (!strcmp("console", direntry->d_name)) {
+ continue;
+ }
+
+ /* skip null */
+ if (!strcmp("null", direntry->d_name)) {
+ continue;
+ }
+
+ snprintf(devname, sizeof(devname), "/dev/%s", direntry->d_name);
+
+ int sensfd = ::open(devname, 0);
+
+ if (sensfd < 0) {
+ warn("failed opening device %s", devname);
+ continue;
+ }
+
+ int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 1);
close(sensfd);
- printf("Disabling %s\n: %s", direntry->d_name, (!block_ret) ? "OK" : "FAIL");
+ printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR");
}
-
closedir(d);
+ ret = TRANSITION_CHANGED;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
- warnx("directory listing ok (FS mounted and readable)");
} else {
/* failed opening dir */
- warnx("FAILED LISTING DEVICE ROOT DIRECTORY");
- return 1;
+ mavlink_log_info(mavlink_fd, "FAILED LISTING DEVICE ROOT DIRECTORY");
+ ret = TRANSITION_DENIED;
}
+ } else {
+ mavlink_log_critical(mavlink_fd, "Not switching to HIL when armed");
+ ret = TRANSITION_DENIED;
}
-
break;
default:
- warnx("Unknown hil state");
+ warnx("Unknown HIL state");
break;
}
}
- if (valid_transition) {
+ if (ret == TRANSITION_CHANGED) {
current_status->hil_state = new_state;
-
current_status->timestamp = hrt_absolute_time();
+ // XXX also set lockdown here
orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+ }
+ return ret;
+}
- current_control_mode->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, current_control_mode);
+/**
+ * Check failsafe and main status and set navigation status for navigator accordingly
+ */
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished)
+{
+ navigation_state_t nav_state_old = status->nav_state;
+
+ bool armed = (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR);
+ status->failsafe = false;
+
+ /* evaluate main state to decide in normal (non-failsafe) mode */
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ case MAIN_STATE_MANUAL:
+ case MAIN_STATE_ALTCTL:
+ case MAIN_STATE_POSCTL:
+ /* require RC for all manual modes */
+ if (status->rc_signal_lost && armed) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- // XXX also set lockdown here
+ } else {
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ status->nav_state = NAVIGATION_STATE_ACRO;
+ break;
+
+ case MAIN_STATE_MANUAL:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+
+ case MAIN_STATE_ALTCTL:
+ status->nav_state = NAVIGATION_STATE_ALTCTL;
+ break;
+
+ case MAIN_STATE_POSCTL:
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ break;
+
+ default:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+ }
+ }
+ break;
+
+ case MAIN_STATE_AUTO_MISSION:
+ /* go into failsafe
+ * - if either the datalink is enabled and lost as well as RC is lost
+ * - if there is no datalink and the mission is finished */
+ if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
+ (!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- ret = OK;
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
+ /* don't bother if RC is lost and mission is not yet finished */
+ } else if (status->rc_signal_lost) {
+
+ /* this mode is ok, we don't need RC for missions */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ }
+ break;
+
+ case MAIN_STATE_AUTO_LOITER:
+ /* go into failsafe if datalink and RC is lost */
+ if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ /* go into failsafe if RC is lost and datalink loss is not set up */
+ } else if (status->rc_signal_lost && !data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ /* don't bother if RC is lost if datalink is connected */
+ } else if (status->rc_signal_lost) {
+
+ /* this mode is ok, we don't need RC for loitering */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ }
+ break;
+
+ case MAIN_STATE_AUTO_RTL:
+ /* require global position and home */
+ if ((!status->condition_global_position_valid || !status->condition_home_position_valid)) {
+ status->failsafe = true;
+
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+ } else {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ }
+ break;
+
+ case MAIN_STATE_OFFBOARD:
+ /* require offboard control, otherwise stay where you are */
+ if (status->offboard_control_signal_lost && !status->rc_signal_lost) {
+ status->failsafe = true;
+
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ } else if (status->offboard_control_signal_lost && status->rc_signal_lost) {
+ status->failsafe = true;
+
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+ } else {
+ status->nav_state = NAVIGATION_STATE_OFFBOARD;
+ }
+ default:
+ break;
}
- return ret;
+ return status->nav_state != nav_state_old;
}
+int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
+{
+ int ret;
+ bool failed = false;
+
+ int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL SENSOR MISSING");
+ failed = true;
+ goto system_eval;
+ }
+
+ ret = ioctl(fd, ACCELIOCSELFTEST, 0);
+
+ if (ret != OK) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL CALIBRATION");
+ failed = true;
+ goto system_eval;
+ }
+
+ /* check measurement result range */
+ struct accel_report acc;
+ ret = read(fd, &acc, sizeof(acc));
+
+ if (ret == sizeof(acc)) {
+ /* evaluate values */
+ float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
+
+ if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE");
+ mavlink_log_critical(mavlink_fd, "hold still while arming");
+ /* this is frickin' fatal */
+ failed = true;
+ goto system_eval;
+ }
+ } else {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL READ");
+ /* this is frickin' fatal */
+ failed = true;
+ goto system_eval;
+ }
+ if (!status->is_rotary_wing) {
+ /* accel done, close it */
+ close(fd);
+ fd = orb_subscribe(ORB_ID(airspeed));
-// /*
-// * Wrapper functions (to be used in the commander), all functions assume lock on current_status
-// */
-
-// /* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR
-// *
-// * START SUBSYSTEM/EMERGENCY FUNCTIONS
-// * */
-
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was removed something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV];
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was disabled something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - gyro disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - accelerometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - magnetometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = (uint8_t)(global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV]);
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - GPS disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-///* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
-//
-//int update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
-//{
-// int ret = 1;
-//
-//// /* Switch on HIL if in standby and not already in HIL mode */
-//// if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
-//// && !current_status->flag_hil_enabled) {
-//// if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
-//// /* Enable HIL on request */
-//// current_status->flag_hil_enabled = true;
-//// ret = OK;
-//// state_machine_publish(status_pub, current_status, mavlink_fd);
-//// publish_armed_status(current_status);
-//// printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
-////
-//// } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
-//// current_status->flag_fmu_armed) {
-////
-//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
-////
-//// } else {
-////
-//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
-//// }
-//// }
-//
-// /* switch manual / auto */
-// if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
-// update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
-// update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
-// update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
-// update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
-// }
-//
-// /* vehicle is disarmed, mode requests arming */
-// if (!(current_status->flag_fmu_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
-// /* only arm in standby state */
-// // XXX REMOVE
-// if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
-// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
-// ret = OK;
-// printf("[cmd] arming due to command request\n");
-// }
-// }
-//
-// /* vehicle is armed, mode requests disarming */
-// if (current_status->flag_fmu_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
-// /* only disarm in ground ready */
-// if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
-// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
-// ret = OK;
-// printf("[cmd] disarming due to command request\n");
-// }
-// }
-//
-// /* NEVER actually switch off HIL without reboot */
-// if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
-// warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
-// mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
-// ret = ERROR;
-// }
-//
-// return ret;
-//}
+ struct airspeed_s airspeed;
+ if ((ret = orb_copy(ORB_ID(airspeed), fd, &airspeed)) ||
+ (hrt_elapsed_time(&airspeed.timestamp) > (50 * 1000))) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED SENSOR MISSING");
+ failed = true;
+ goto system_eval;
+ }
+
+ if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
+ mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION MISSING");
+ // XXX do not make this fatal yet
+ }
+ }
+
+system_eval:
+ close(fd);
+ return (failed);
+}
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 0bfdf36a8..bb1b87e71 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.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
@@ -36,19 +34,18 @@
/**
* @file state_machine_helper.h
* State machine helper functions definitions
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#ifndef STATE_MACHINE_HELPER_H_
#define STATE_MACHINE_HELPER_H_
-#define GPS_NOFIX_COUNTER_LIMIT 4 //need GPS_NOFIX_COUNTER_LIMIT gps packets with a bad fix to call an error (if outdoor)
-#define GPS_GOTFIX_COUNTER_REQUIRED 4 //need GPS_GOTFIX_COUNTER_REQUIRED gps packets with a good fix to obtain position lock
-
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/safety.h>
-#include <uORB/topics/vehicle_control_mode.h>
typedef enum {
TRANSITION_DENIED = -1,
@@ -57,23 +54,17 @@ typedef enum {
} transition_result_t;
-transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
- const struct vehicle_control_mode_s *control_mode, arming_state_t new_arming_state, struct actuator_armed_s *armed);
-
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
-bool check_arming_state_changed();
+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, const int mavlink_fd);
transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
-bool check_main_state_changed();
-
-transition_result_t navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode);
-
-bool check_navigation_state_changed();
+transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
-void set_navigation_state_changed();
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished);
-int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, int control_mode_pub, struct vehicle_control_mode_s *current_control_mode, const int mavlink_fd);
+int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
#endif /* STATE_MACHINE_HELPER_H_ */