aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp (renamed from src/modules/commander/accelerometer_calibration.c)139
-rw-r--r--src/modules/commander/accelerometer_calibration.h3
-rw-r--r--src/modules/commander/airspeed_calibration.cpp121
-rw-r--r--src/modules/commander/airspeed_calibration.h46
-rw-r--r--src/modules/commander/baro_calibration.cpp60
-rw-r--r--src/modules/commander/baro_calibration.h46
-rw-r--r--src/modules/commander/calibration_routines.cpp (renamed from src/modules/commander/calibration_routines.c)3
-rw-r--r--src/modules/commander/commander.c2097
-rw-r--r--src/modules/commander/commander.cpp1793
-rw-r--r--src/modules/commander/commander_helper.cpp259
-rw-r--r--src/modules/commander/commander_helper.h87
-rw-r--r--src/modules/commander/commander_params.c (renamed from src/modules/commander/commander.h)32
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp55
-rw-r--r--src/modules/commander/commander_tests/module.mk41
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp247
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h44
-rw-r--r--src/modules/commander/gyro_calibration.cpp289
-rw-r--r--src/modules/commander/gyro_calibration.h46
-rw-r--r--src/modules/commander/mag_calibration.cpp298
-rw-r--r--src/modules/commander/mag_calibration.h46
-rw-r--r--src/modules/commander/module.mk15
-rw-r--r--src/modules/commander/px4_custom_mode.h37
-rw-r--r--src/modules/commander/rc_calibration.cpp88
-rw-r--r--src/modules/commander/rc_calibration.h46
-rw-r--r--src/modules/commander/state_machine_helper.c757
-rw-r--r--src/modules/commander/state_machine_helper.cpp703
-rw-r--r--src/modules/commander/state_machine_helper.h168
27 files changed, 4480 insertions, 3086 deletions
diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.cpp
index fbb73d997..ed6707f04 100644
--- a/src/modules/commander/accelerometer_calibration.c
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -33,7 +33,7 @@
****************************************************************************/
/**
- * @file accelerometer_calibration.c
+ * @file accelerometer_calibration.cpp
*
* Implementation of accelerometer calibration.
*
@@ -104,32 +104,44 @@
*/
#include "accelerometer_calibration.h"
+#include "commander_helper.h"
+#include <unistd.h>
+#include <stdio.h>
#include <poll.h>
+#include <fcntl.h>
+#include <sys/prctl.h>
+#include <math.h>
+#include <string.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_combined.h>
#include <drivers/drv_accel.h>
-#include <systemlib/conversions.h>
+#include <geo/geo.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <mavlink/mavlink_log.h>
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]);
int detect_orientation(int mavlink_fd, int sub_sensor_combined);
int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
int mat_invert3(float src[3][3], float dst[3][3]);
int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g);
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) {
+int do_accel_calibration(int mavlink_fd) {
/* announce change */
mavlink_log_info(mavlink_fd, "accel calibration started");
- /* set to accel calibration mode */
- status->flag_preflight_accel_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
+ mavlink_log_info(mavlink_fd, "accel cal progress <0> percent");
/* measure and calculate offsets & scales */
float accel_offs[3];
float accel_scale[3];
- int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs, accel_scale);
+ int res = do_accel_calibration_measurements(mavlink_fd, accel_offs, accel_scale);
if (res == OK) {
/* measurements complete successfully, set parameters */
@@ -165,24 +177,17 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m
}
mavlink_log_info(mavlink_fd, "accel calibration done");
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
+ return OK;
} else {
/* measurements error */
mavlink_log_info(mavlink_fd, "accel calibration aborted");
- tune_error();
- sleep(2);
+ return ERROR;
}
/* exit accel calibration mode */
- status->flag_preflight_accel_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
}
-int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
+int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) {
const int samples_num = 2500;
float accel_ref[6][3];
bool data_collected[6] = { false, false, false, false, false, false };
@@ -207,38 +212,52 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float
}
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+
+ unsigned done_count = 0;
+
while (true) {
bool done = true;
- char str[80];
- int str_ptr;
- str_ptr = sprintf(str, "keep vehicle still:");
+ unsigned old_done_count = done_count;
+ done_count = 0;
+
for (int i = 0; i < 6; i++) {
if (!data_collected[i]) {
- str_ptr += sprintf(&(str[str_ptr]), " %s", orientation_strs[i]);
done = false;
}
}
+
+ mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
+ (!data_collected[0]) ? "x+ " : "",
+ (!data_collected[1]) ? "x- " : "",
+ (!data_collected[2]) ? "y+ " : "",
+ (!data_collected[3]) ? "y- " : "",
+ (!data_collected[4]) ? "z+ " : "",
+ (!data_collected[5]) ? "z- " : "");
+
+ if (old_done_count != done_count)
+ mavlink_log_info(mavlink_fd, "accel cal progress <%u> percent", 17 * done_count);
+
if (done)
break;
- mavlink_log_info(mavlink_fd, str);
int orient = detect_orientation(mavlink_fd, sensor_combined_sub);
if (orient < 0)
return ERROR;
if (data_collected[orient]) {
- sprintf(str, "%s direction already measured, please rotate", orientation_strs[orient]);
- mavlink_log_info(mavlink_fd, str);
+ mavlink_log_info(mavlink_fd, "%s done, please rotate to a different axis", orientation_strs[orient]);
continue;
}
- sprintf(str, "meas started: %s", orientation_strs[orient]);
- mavlink_log_info(mavlink_fd, str);
+ mavlink_log_info(mavlink_fd, "accel measurement started: %s axis", orientation_strs[orient]);
read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num);
- str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient], accel_ref[orient][0], accel_ref[orient][1], accel_ref[orient][2]);
- mavlink_log_info(mavlink_fd, str);
+ mavlink_log_info(mavlink_fd, "result for %s axis: [ %.2f %.2f %.2f ]", orientation_strs[orient],
+ (double)accel_ref[orient][0],
+ (double)accel_ref[orient][1],
+ (double)accel_ref[orient][2]);
+
data_collected[orient] = true;
- tune_confirm();
+ tune_neutral();
}
close(sensor_combined_sub);
@@ -246,7 +265,7 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float
float accel_T[3][3];
int res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G);
if (res != 0) {
- mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error");
+ mavlink_log_info(mavlink_fd, "ERROR: calibration values calculation error");
return ERROR;
}
@@ -279,8 +298,10 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
/* set accel error threshold to 5m/s^2 */
float accel_err_thr = 5.0f;
/* still time required in us */
- int64_t still_time = 2000000;
- struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
+ hrt_abstime still_time = 2000000;
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_combined;
+ fds[0].events = POLLIN;
hrt_abstime t_start = hrt_absolute_time();
/* set timeout to 30s */
@@ -316,12 +337,12 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
/* is still now */
if (t_still == 0) {
/* first time */
- mavlink_log_info(mavlink_fd, "still...");
+ mavlink_log_info(mavlink_fd, "detected rest position, waiting...");
t_still = t;
t_timeout = t + timeout;
} else {
/* still since t_still */
- if ((int64_t) t - (int64_t) t_still > still_time) {
+ if (t > t_still + still_time) {
/* vehicle is still, exit from the loop to detection of its orientation */
break;
}
@@ -331,7 +352,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
accel_disp[2] > still_thr2 * 2.0f) {
/* not still, reset still start time */
if (t_still != 0) {
- mavlink_log_info(mavlink_fd, "moving...");
+ mavlink_log_info(mavlink_fd, "detected motion, please hold still...");
t_still = 0;
}
}
@@ -343,34 +364,34 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
}
if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: failed reading accel");
+ mavlink_log_info(mavlink_fd, "ERROR: Failed reading sensor");
return -1;
}
}
- if ( fabs(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
+ 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 ]
- if ( fabs(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
+ 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 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
+ 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 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabs(accel_ema[2]) < accel_err_thr )
+ 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 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr )
+ 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 ]
- if ( fabs(accel_ema[0]) < accel_err_thr &&
- fabs(accel_ema[1]) < accel_err_thr &&
- fabs(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr )
+ 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 ]
mavlink_log_info(mavlink_fd, "ERROR: invalid orientation");
@@ -382,7 +403,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
* Read specified number of accelerometer samples, calculate average and dispersion.
*/
int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num) {
- struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } };
+ struct pollfd fds[1];
+ fds[0].fd = sensor_combined_sub;
+ fds[0].events = POLLIN;
int count = 0;
float accel_sum[3] = { 0.0f, 0.0f, 0.0f };
@@ -416,7 +439,7 @@ int mat_invert3(float src[3][3], float dst[3][3]) {
float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) -
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.0)
+ if (det == 0.0f)
return ERROR; // Singular matrix
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h
index f93a867ba..1cf9c0977 100644
--- a/src/modules/commander/accelerometer_calibration.h
+++ b/src/modules/commander/accelerometer_calibration.h
@@ -44,8 +44,7 @@
#define ACCELEROMETER_CALIBRATION_H_
#include <stdint.h>
-#include <uORB/topics/vehicle_status.h>
-void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd);
+int do_accel_calibration(int mavlink_fd);
#endif /* ACCELEROMETER_CALIBRATION_H_ */
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
new file mode 100644
index 000000000..e414e5f70
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -0,0 +1,121 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file airspeed_calibration.cpp
+ * Airspeed sensor calibration routine
+ */
+
+#include "airspeed_calibration.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/differential_pressure.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_airspeed_calibration(int mavlink_fd)
+{
+ /* give directions */
+ mavlink_log_info(mavlink_fd, "airspeed calibration starting, keep it still");
+
+ const int calibration_count = 2500;
+
+ 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;
+
+ while (calibration_counter < calibration_count) {
+
+ /* 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);
+ diff_pres_offset += diff_pres.differential_pressure_pa;
+ calibration_counter++;
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_info(mavlink_fd, "airspeed calibration aborted");
+ return ERROR;
+ }
+ }
+
+ diff_pres_offset = diff_pres_offset / calibration_count;
+
+ if (isfinite(diff_pres_offset)) {
+
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, "Setting offs failed!");
+ return ERROR;
+ }
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ mavlink_log_info(mavlink_fd, "FAILED storing calibration");
+ return ERROR;
+ }
+
+ //char buf[50];
+ //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
+ //mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "airspeed calibration done");
+
+ return OK;
+
+ } else {
+ mavlink_log_info(mavlink_fd, "airspeed calibration FAILED (NaN)");
+ return ERROR;
+ }
+}
diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h
new file mode 100644
index 000000000..71c701fc2
--- /dev/null
+++ b/src/modules/commander/airspeed_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gyro_calibration.h
+ * Airspeed sensor calibration routine
+ */
+
+#ifndef AIRSPEED_CALIBRATION_H_
+#define AIRSPEED_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_airspeed_calibration(int mavlink_fd);
+
+#endif /* AIRSPEED_CALIBRATION_H_ */
diff --git a/src/modules/commander/baro_calibration.cpp b/src/modules/commander/baro_calibration.cpp
new file mode 100644
index 000000000..3123c4087
--- /dev/null
+++ b/src/modules/commander/baro_calibration.cpp
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file baro_calibration.cpp
+ * Barometer calibration routine
+ */
+
+#include "baro_calibration.h"
+
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_baro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_baro_calibration(int mavlink_fd)
+{
+ // TODO implement this
+ return ERROR;
+}
diff --git a/src/modules/commander/baro_calibration.h b/src/modules/commander/baro_calibration.h
new file mode 100644
index 000000000..bc42bc6cf
--- /dev/null
+++ b/src/modules/commander/baro_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mag_calibration.h
+ * Barometer calibration routine
+ */
+
+#ifndef BARO_CALIBRATION_H_
+#define BARO_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_baro_calibration(int mavlink_fd);
+
+#endif /* BARO_CALIBRATION_H_ */
diff --git a/src/modules/commander/calibration_routines.c b/src/modules/commander/calibration_routines.cpp
index a26938637..be38ea104 100644
--- a/src/modules/commander/calibration_routines.c
+++ b/src/modules/commander/calibration_routines.cpp
@@ -33,7 +33,7 @@
****************************************************************************/
/**
- * @file calibration_routines.c
+ * @file calibration_routines.cpp
* Calibration routines implementations.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
@@ -217,3 +217,4 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
return 0;
}
+
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
deleted file mode 100644
index e9d1f3954..000000000
--- a/src/modules/commander/commander.c
+++ /dev/null
@@ -1,2097 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 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>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file commander.c
- * Main system state machine implementation.
- *
- * @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 <joes@student.ethz.ch>
- *
- */
-
-#include "commander.h"
-
-#include <nuttx/config.h>
-#include <pthread.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <stdbool.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <debug.h>
-#include <sys/prctl.h>
-#include <string.h>
-#include <drivers/drv_led.h>
-#include <drivers/drv_hrt.h>
-#include <drivers/drv_tone_alarm.h>
-#include "state_machine_helper.h"
-#include "systemlib/systemlib.h"
-#include <math.h>
-#include <poll.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/battery_status.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/offboard_control_setpoint.h>
-#include <uORB/topics/home_position.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/subsystem_info.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/differential_pressure.h>
-#include <mavlink/mavlink_log.h>
-
-#include <systemlib/param/param.h>
-#include <systemlib/systemlib.h>
-#include <systemlib/err.h>
-
-/* XXX MOVE CALIBRATION TO SENSORS APP THREAD */
-#include <drivers/drv_accel.h>
-#include <drivers/drv_gyro.h>
-#include <drivers/drv_mag.h>
-#include <drivers/drv_baro.h>
-
-#include "calibration_routines.h"
-#include "accelerometer_calibration.h"
-
-PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */
-//PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */
-PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
-PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
-PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
-
-#include <systemlib/cpuload.h>
-extern struct system_load_s system_load;
-
-/* Decouple update interval and hysteris counters, all depends on intervals */
-#define COMMANDER_MONITORING_INTERVAL 50000
-#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
-#define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-#define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-#define STICK_ON_OFF_LIMIT 0.75f
-#define STICK_THRUST_RANGE 1.0f
-#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
-#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-#define GPS_FIX_TYPE_2D 2
-#define GPS_FIX_TYPE_3D 3
-#define GPS_QUALITY_GOOD_HYSTERIS_TIME_MS 5000
-#define GPS_QUALITY_GOOD_COUNTER_LIMIT (GPS_QUALITY_GOOD_HYSTERIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-
-/* File descriptors */
-static int leds;
-static int buzzer;
-static int mavlink_fd;
-static bool commander_initialized = false;
-static struct vehicle_status_s current_status; /**< Main state machine */
-static orb_advert_t stat_pub;
-
-// static uint16_t nofix_counter = 0;
-// static uint16_t gotfix_counter = 0;
-
-static unsigned int failsafe_lowlevel_timeout_ms;
-
-static bool thread_should_exit = false; /**< daemon exit flag */
-static bool thread_running = false; /**< daemon status flag */
-static int daemon_task; /**< Handle of daemon task / thread */
-
-/* pthread loops */
-static void *orb_receive_loop(void *arg);
-
-__EXPORT int commander_main(int argc, char *argv[]);
-
-/**
- * Mainloop of commander.
- */
-int commander_thread_main(int argc, char *argv[]);
-
-static int buzzer_init(void);
-static void buzzer_deinit(void);
-static int led_init(void);
-static void led_deinit(void);
-static int led_toggle(int led);
-static int led_on(int led);
-static int led_off(int led);
-static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_mag_calibration(int status_pub, struct vehicle_status_s *status);
-static void do_rc_calibration(int status_pub, struct vehicle_status_s *status);
-static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd);
-
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state);
-
-
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-/**
- * Sort calibration values.
- *
- * Sorts the calibration values with bubble sort.
- *
- * @param a The array to sort
- * @param n The number of entries in the array
- */
-// static void cal_bsort(float a[], int n);
-
-static int buzzer_init()
-{
- buzzer = open("/dev/tone_alarm", O_WRONLY);
-
- if (buzzer < 0) {
- warnx("Buzzer: open fail\n");
- return ERROR;
- }
-
- return 0;
-}
-
-static void buzzer_deinit()
-{
- close(buzzer);
-}
-
-
-static int led_init()
-{
- leds = open(LED_DEVICE_PATH, 0);
-
- if (leds < 0) {
- warnx("LED: open fail\n");
- return ERROR;
- }
-
- if (ioctl(leds, LED_ON, LED_BLUE) || ioctl(leds, LED_ON, LED_AMBER)) {
- warnx("LED: ioctl fail\n");
- return ERROR;
- }
-
- return 0;
-}
-
-static void led_deinit()
-{
- close(leds);
-}
-
-static int led_toggle(int led)
-{
- static int last_blue = LED_ON;
- static int last_amber = LED_ON;
-
- if (led == LED_BLUE) last_blue = (last_blue == LED_ON) ? LED_OFF : LED_ON;
-
- if (led == LED_AMBER) last_amber = (last_amber == LED_ON) ? LED_OFF : LED_ON;
-
- return ioctl(leds, ((led == LED_BLUE) ? last_blue : last_amber), led);
-}
-
-static int led_on(int led)
-{
- return ioctl(leds, LED_ON, led);
-}
-
-static int led_off(int led)
-{
- return ioctl(leds, LED_OFF, led);
-}
-
-enum AUDIO_PATTERN {
- AUDIO_PATTERN_ERROR = 2,
- AUDIO_PATTERN_NOTIFY_POSITIVE = 3,
- AUDIO_PATTERN_NOTIFY_NEUTRAL = 4,
- AUDIO_PATTERN_NOTIFY_NEGATIVE = 5,
- AUDIO_PATTERN_NOTIFY_CHARGE = 6
-};
-
-int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state)
-{
-
- /* Trigger alarm if going into any error state */
- if (((new_state == SYSTEM_STATE_GROUND_ERROR) && (old_state != SYSTEM_STATE_GROUND_ERROR)) ||
- ((new_state == SYSTEM_STATE_MISSION_ABORT) && (old_state != SYSTEM_STATE_MISSION_ABORT))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_ERROR);
- }
-
- /* Trigger neutral on arming / disarming */
- if (((new_state == SYSTEM_STATE_GROUND_READY) && (old_state != SYSTEM_STATE_GROUND_READY))) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, AUDIO_PATTERN_NOTIFY_NEUTRAL);
- }
-
- /* Trigger Tetris on being bored */
-
- return 0;
-}
-
-void tune_confirm(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 3);
-}
-
-void tune_error(void)
-{
- ioctl(buzzer, TONE_SET_ALARM, 4);
-}
-
-void do_rc_calibration(int status_pub, struct vehicle_status_s *status)
-{
- if (current_status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
- return;
- }
-
- int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
- struct manual_control_setpoint_s sp;
- orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
-
- /* set parameters */
-
- float p = sp.roll;
- param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
- param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
- param_set(param_find("TRIM_YAW"), &p);
-
- /* store to permanent storage */
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
- }
-
- mavlink_log_info(mavlink_fd, "trim calibration done");
-}
-
-void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
-{
-
- /* set to mag calibration mode */
- status->flag_preflight_mag_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
- struct mag_report mag;
-
- /* 45 seconds */
- uint64_t calibration_interval = 45 * 1000 * 1000;
-
- /* maximum 2000 values */
- const unsigned int calibration_maxcount = 500;
- unsigned int calibration_counter = 0;
-
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
-
- // XXX old cal
- // * FLT_MIN is not the most negative float number,
- // * but the smallest number by magnitude float can
- // * represent. Use -FLT_MAX to initialize the most
- // * negative number
-
- // float mag_max[3] = {-FLT_MAX, -FLT_MAX, -FLT_MAX};
- // float mag_min[3] = {FLT_MAX, FLT_MAX, FLT_MAX};
-
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
-
- /* erase old calibration */
- struct mag_scale mscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set scale / offsets for mag");
- mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
- }
-
- /* calibrate range */
- if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
- warnx("failed to calibrate scale");
- }
-
- close(fd);
-
- /* calibrate offsets */
-
- // uint64_t calibration_start = hrt_absolute_time();
-
- uint64_t axis_deadline = hrt_absolute_time();
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
-
- const char axislabels[3] = { 'X', 'Y', 'Z'};
- int axis_index = -1;
-
- float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
-
- if (x == NULL || y == NULL || z == NULL) {
- warnx("mag cal failed: out of memory");
- mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
- warnx("x:%p y:%p z:%p\n", x, y, z);
- return;
- }
-
- tune_confirm();
- sleep(2);
- tune_confirm();
-
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_mag, .events = POLLIN } };
-
- /* user guidance */
- if (hrt_absolute_time() >= axis_deadline &&
- axis_index < 3) {
-
- axis_index++;
-
- char buf[50];
- sprintf(buf, "Please rotate around %c", axislabels[axis_index]);
- mavlink_log_info(mavlink_fd, buf);
- tune_confirm();
-
- axis_deadline += calibration_interval / 3;
- }
-
- if (!(axis_index < 3)) {
- break;
- }
-
- // int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
-
- // if ((axis_left / 1000) == 0 && axis_left > 0) {
- // char buf[50];
- // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
- // mavlink_log_info(mavlink_fd, buf);
- // }
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
-
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
-
- /* get min/max values */
-
- // if (mag.x < mag_min[0]) {
- // mag_min[0] = mag.x;
- // }
- // else if (mag.x > mag_max[0]) {
- // mag_max[0] = mag.x;
- // }
-
- // if (raw.magnetometer_ga[1] < mag_min[1]) {
- // mag_min[1] = raw.magnetometer_ga[1];
- // }
- // else if (raw.magnetometer_ga[1] > mag_max[1]) {
- // mag_max[1] = raw.magnetometer_ga[1];
- // }
-
- // if (raw.magnetometer_ga[2] < mag_min[2]) {
- // mag_min[2] = raw.magnetometer_ga[2];
- // }
- // else if (raw.magnetometer_ga[2] > mag_max[2]) {
- // mag_max[2] = raw.magnetometer_ga[2];
- // }
-
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "mag cal canceled (timed out)");
- break;
- }
- }
-
- float sphere_x;
- float sphere_y;
- float sphere_z;
- float sphere_radius;
-
- sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
-
- free(x);
- free(y);
- free(z);
-
- if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
-
- fd = open(MAG_DEVICE_PATH, 0);
-
- struct mag_scale mscale;
-
- if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to get scale / offsets for mag");
-
- mscale.x_offset = sphere_x;
- mscale.y_offset = sphere_y;
- mscale.z_offset = sphere_z;
-
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to set scale / offsets for mag");
-
- close(fd);
-
- /* announce and set new offset */
-
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
- warnx("Setting X mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
- warnx("Setting Y mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
- warnx("Setting Z mag offset failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
- warnx("Setting X mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
- warnx("Setting Y mag scale failed!\n");
- }
-
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
- warnx("Setting Z mag scale failed!\n");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- mavlink_log_info(mavlink_fd, "FAILED storing calibration");
- }
-
- warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
- (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
- (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
-
- char buf[52];
- sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
- (double)mscale.y_offset, (double)mscale.z_offset);
- mavlink_log_info(mavlink_fd, buf);
-
- sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
- (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, buf);
-
- mavlink_log_info(mavlink_fd, "mag calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
- }
-
- /* disable calibration mode */
- status->flag_preflight_mag_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(sub_mag);
-}
-
-void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
-{
- /* set to gyro calibration mode */
- status->flag_preflight_gyro_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 5000;
-
- int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s raw;
-
- int calibration_counter = 0;
- float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
-
- /* set offsets to zero */
- int fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale_null = {
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- 0.0f,
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- int errcount = 0;
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- gyro_offset[0] += raw.gyro_rad_s[0];
- gyro_offset[1] += raw.gyro_rad_s[1];
- gyro_offset[2] += raw.gyro_rad_s[2];
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- errcount++;
- }
-
- if (errcount > 1000) {
- /* any persisting poll error is a reason to abort */
- mavlink_log_info(mavlink_fd, "permanent gyro error, aborted.");
- return;
- }
- }
-
- gyro_offset[0] = gyro_offset[0] / calibration_count;
- gyro_offset[1] = gyro_offset[1] / calibration_count;
- gyro_offset[2] = gyro_offset[2] / calibration_count;
-
- /* exit gyro calibration mode */
- status->flag_preflight_gyro_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
-
- if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
- || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
- || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
- }
-
- /* set offsets to actual value */
- fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- 1.0f,
- gyro_offset[1],
- 1.0f,
- gyro_offset[2],
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- // char buf[50];
- // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
- // mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "gyro calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
- }
-
- close(sub_sensor_combined);
-}
-
-void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
-{
- /* announce change */
-
- mavlink_log_info(mavlink_fd, "keep it still");
- /* set to accel calibration mode */
- status->flag_preflight_airspeed_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- const int calibration_count = 2500;
-
- 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;
-
- while (calibration_counter < calibration_count) {
-
- /* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } };
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret) {
- orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
- calibration_counter++;
-
- } else if (poll_ret == 0) {
- /* any poll failure for 1s is a reason to abort */
- mavlink_log_info(mavlink_fd, "airspeed calibration aborted");
- return;
- }
- }
-
- diff_pres_offset = diff_pres_offset / calibration_count;
-
- if (isfinite(diff_pres_offset)) {
-
- if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
- mavlink_log_critical(mavlink_fd, "Setting offs failed!");
- }
-
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
-
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- }
-
- //char buf[50];
- //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]);
- //mavlink_log_info(mavlink_fd, buf);
- mavlink_log_info(mavlink_fd, "airspeed calibration done");
-
- tune_confirm();
- sleep(2);
- tune_confirm();
- sleep(2);
- /* third beep by cal end routine */
-
- } else {
- mavlink_log_info(mavlink_fd, "airspeed calibration FAILED (NaN)");
- }
-
- /* exit airspeed calibration mode */
- status->flag_preflight_airspeed_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
-
- close(diff_pres_sub);
-}
-
-
-
-void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_status, struct vehicle_command_s *cmd)
-{
- /* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
-
- /* announce command handling */
- tune_confirm();
-
-
- /* supported command handling start */
-
- /* request to set different system mode */
- switch (cmd->command) {
- case VEHICLE_CMD_DO_SET_MODE: {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, (uint8_t)cmd->param1)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- break;
-
- case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- /* request to arm */
- if ((int)cmd->param1 == 1) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- /* request to disarm */
-
- } else if ((int)cmd->param1 == 0) {
- if (OK == update_state_machine_mode_request(status_pub, current_vehicle_status, mavlink_fd, VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- }
- break;
-
- /* request for an autopilot reboot */
- case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: {
- if ((int)cmd->param1 == 1) {
- if (OK == do_state_update(status_pub, current_vehicle_status, mavlink_fd, SYSTEM_STATE_REBOOT)) {
- /* SPECIAL CASE: SYSTEM WILL NEVER RETURN HERE */
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- /* system may return here */
- result = VEHICLE_CMD_RESULT_DENIED;
- }
- }
- }
- break;
-
-// /* request to land */
-// case VEHICLE_CMD_NAV_LAND:
-// {
-// //TODO: add check if landing possible
-// //TODO: add landing maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_ARMED)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// } }
-// break;
-//
-// /* request to takeoff */
-// case VEHICLE_CMD_NAV_TAKEOFF:
-// {
-// //TODO: add check if takeoff possible
-// //TODO: add takeoff maneuver
-//
-// if (0 == update_state_machine_custom_mode_request(status_pub, current_vehicle_status, SYSTEM_STATE_AUTO)) {
-// result = VEHICLE_CMD_RESULT_ACCEPTED;
-// }
-// }
-// break;
-//
- /* preflight calibration */
- case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
- bool handled = false;
-
- /* gyro calibration */
- if ((int)(cmd->param1) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting gyro cal");
- tune_confirm();
- do_gyro_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished gyro cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING gyro cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* magnetometer calibration */
- if ((int)(cmd->param2) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting mag cal");
- tune_confirm();
- do_mag_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished mag cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING mag cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* zero-altitude pressure calibration */
- if ((int)(cmd->param3) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "zero altitude cal. not implemented");
- tune_confirm();
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING altitude calibration");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* trim calibration */
- if ((int)(cmd->param4) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "starting trim cal");
- tune_confirm();
- do_rc_calibration(status_pub, &current_status);
- mavlink_log_info(mavlink_fd, "finished trim cal");
- tune_confirm();
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING trim cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* accel calibration */
- if ((int)(cmd->param5) == 1) {
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting accel cal");
- tune_confirm();
- do_accel_calibration(status_pub, &current_status, mavlink_fd);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished accel cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING accel cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* airspeed calibration */
- if ((int)(cmd->param6) == 1) { //xxx: this is not defined by the mavlink protocol
- /* transition to calibration state */
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_PREFLIGHT);
-
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) {
- mavlink_log_info(mavlink_fd, "CMD starting airspeed cal");
- tune_confirm();
- do_airspeed_calibration(status_pub, &current_status);
- tune_confirm();
- mavlink_log_info(mavlink_fd, "CMD finished airspeed cal");
- do_state_update(status_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING airspeed cal");
- result = VEHICLE_CMD_RESULT_DENIED;
- }
-
- handled = true;
- }
-
- /* none found */
- if (!handled) {
- //warnx("refusing unsupported calibration request\n");
- mavlink_log_critical(mavlink_fd, "CMD refusing unsup. calib. request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- }
- }
- break;
-
- case VEHICLE_CMD_PREFLIGHT_STORAGE: {
- if (current_status.flag_system_armed &&
- ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR))) {
- /* do not perform expensive memory tasks on multirotors in flight */
- // XXX this is over-safe, as soon as cmd is in low prio thread this can be allowed
- mavlink_log_info(mavlink_fd, "REJECTING save cmd while multicopter armed");
-
- } else {
-
- // XXX move this to LOW PRIO THREAD of commander app
- /* Read all parameters from EEPROM to RAM */
-
- if (((int)(cmd->param1)) == 0) {
-
- /* read all parameters from EEPROM to RAM */
- int read_ret = param_load_default();
-
- if (read_ret == OK) {
- //warnx("[mavlink pm] Loaded EEPROM params in RAM\n");
- mavlink_log_info(mavlink_fd, "OK loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else if (read_ret == 1) {
- mavlink_log_info(mavlink_fd, "OK no changes in");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- if (read_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR loading params from");
- mavlink_log_info(mavlink_fd, param_get_default_file());
-
- } else {
- mavlink_log_info(mavlink_fd, "ERR no param file named");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
-
- result = VEHICLE_CMD_RESULT_FAILED;
- }
-
- } else if (((int)(cmd->param1)) == 1) {
-
- /* write all parameters from RAM to EEPROM */
- int write_ret = param_save_default();
-
- if (write_ret == OK) {
- mavlink_log_info(mavlink_fd, "OK saved param file");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- result = VEHICLE_CMD_RESULT_ACCEPTED;
-
- } else {
- if (write_ret < -1) {
- mavlink_log_info(mavlink_fd, "ERR params file does not exit:");
- mavlink_log_info(mavlink_fd, param_get_default_file());
-
- } else {
- mavlink_log_info(mavlink_fd, "ERR writing params to");
- mavlink_log_info(mavlink_fd, param_get_default_file());
- }
-
- result = VEHICLE_CMD_RESULT_FAILED;
- }
-
- } else {
- mavlink_log_info(mavlink_fd, "[pm] refusing unsupp. STOR request");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- }
- }
- }
- break;
-
- default: {
- mavlink_log_critical(mavlink_fd, "[cmd] refusing unsupported command");
- result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- /* announce command rejection */
- ioctl(buzzer, TONE_SET_ALARM, 4);
- }
- break;
- }
-
- /* supported command handling stop */
- if (result == VEHICLE_CMD_RESULT_FAILED ||
- result == VEHICLE_CMD_RESULT_DENIED ||
- result == VEHICLE_CMD_RESULT_UNSUPPORTED) {
- ioctl(buzzer, TONE_SET_ALARM, 5);
-
- } else if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
- tune_confirm();
- }
-
- /* send any requested ACKs */
- if (cmd->confirmation > 0) {
- /* send acknowledge command */
- // XXX TODO
- }
-
-}
-
-static void *orb_receive_loop(void *arg) //handles status information coming from subsystems (present, enabled, health), these values do not indicate the quality (variance) of the signal
-{
- /* Set thread name */
- prctl(PR_SET_NAME, "commander orb rcv", getpid());
-
- /* Subscribe to command topic */
- int subsys_sub = orb_subscribe(ORB_ID(subsystem_info));
- struct subsystem_info_s info;
-
- struct vehicle_status_s *vstatus = (struct vehicle_status_s *)arg;
-
- while (!thread_should_exit) {
- struct pollfd fds[1] = { { .fd = subsys_sub, .events = POLLIN } };
-
- if (poll(fds, 1, 5000) == 0) {
- /* timeout, but this is no problem, silently ignore */
- } else {
- /* got command */
- orb_copy(ORB_ID(subsystem_info), subsys_sub, &info);
-
- warnx("Subsys changed: %d\n", (int)info.subsystem_type);
-
- /* mark / unmark as present */
- if (info.present) {
- vstatus->onboard_control_sensors_present |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_present &= ~info.subsystem_type;
- }
-
- /* mark / unmark as enabled */
- if (info.enabled) {
- vstatus->onboard_control_sensors_enabled |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_enabled &= ~info.subsystem_type;
- }
-
- /* mark / unmark as ok */
- if (info.ok) {
- vstatus->onboard_control_sensors_health |= info.subsystem_type;
-
- } else {
- vstatus->onboard_control_sensors_health &= ~info.subsystem_type;
- }
- }
- }
-
- close(subsys_sub);
-
- return NULL;
-}
-
-/*
- * Provides a coarse estimate of remaining battery power.
- *
- * The estimate is very basic and based on decharging voltage curves.
- *
- * @return the estimated remaining capacity in 0..1
- */
-float battery_remaining_estimate_voltage(float voltage);
-
-PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.2f);
-PARAM_DEFINE_FLOAT(BAT_V_FULL, 4.05f);
-PARAM_DEFINE_FLOAT(BAT_N_CELLS, 3);
-
-float battery_remaining_estimate_voltage(float voltage)
-{
- float ret = 0;
- static param_t bat_volt_empty;
- static param_t bat_volt_full;
- static param_t bat_n_cells;
- static bool initialized = false;
- static unsigned int counter = 0;
- static float ncells = 3;
- // XXX change cells to int (and param to INT32)
-
- if (!initialized) {
- bat_volt_empty = param_find("BAT_V_EMPTY");
- bat_volt_full = param_find("BAT_V_FULL");
- bat_n_cells = param_find("BAT_N_CELLS");
- initialized = true;
- }
-
- static float chemistry_voltage_empty = 3.2f;
- static float chemistry_voltage_full = 4.05f;
-
- if (counter % 100 == 0) {
- param_get(bat_volt_empty, &chemistry_voltage_empty);
- param_get(bat_volt_full, &chemistry_voltage_full);
- param_get(bat_n_cells, &ncells);
- }
-
- counter++;
-
- ret = (voltage - ncells * chemistry_voltage_empty) / (ncells * (chemistry_voltage_full - chemistry_voltage_empty));
-
- /* limit to sane values */
- ret = (ret < 0) ? 0 : ret;
- ret = (ret > 1) ? 1 : ret;
- return ret;
-}
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
- exit(1);
-}
-
-/**
- * The daemon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int commander_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- warnx("commander already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- daemon_task = task_spawn_cmd("commander",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 40,
- 3000,
- commander_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("\tcommander is running\n");
-
- } else {
- warnx("\tcommander not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int commander_thread_main(int argc, char *argv[])
-{
- /* not yet initialized */
- commander_initialized = false;
- bool home_position_set = false;
-
- /* set parameters */
- failsafe_lowlevel_timeout_ms = 0;
- param_get(param_find("SYS_FAILSAVE_LL"), &failsafe_lowlevel_timeout_ms);
-
- 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");
-
- /* welcome user */
- warnx("I am in command now!\n");
-
- /* pthreads for command and subsystem info handling */
- // pthread_t command_handling_thread;
- pthread_t subsystem_info_thread;
-
- /* initialize */
- if (led_init() != 0) {
- warnx("ERROR: Failed to initialize leds\n");
- }
-
- if (buzzer_init() != 0) {
- warnx("ERROR: Failed to initialize buzzer\n");
- }
-
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- if (mavlink_fd < 0) {
- warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n");
- }
-
- /* make sure we are in preflight state */
- memset(&current_status, 0, sizeof(current_status));
- current_status.state_machine = SYSTEM_STATE_PREFLIGHT;
- current_status.flag_system_armed = false;
- /* neither manual nor offboard control commands have been received */
- current_status.offboard_control_signal_found_once = false;
- current_status.rc_signal_found_once = false;
- /* mark all signals lost as long as they haven't been found */
- current_status.rc_signal_lost = true;
- current_status.offboard_control_signal_lost = true;
- /* allow manual override initially */
- current_status.flag_external_manual_override_ok = true;
- /* flag position info as bad, do not allow auto mode */
- current_status.flag_vector_flight_mode_ok = false;
- /* set battery warning flag */
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
-
- /* advertise to ORB */
- stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
- /* publish current state machine */
- state_machine_publish(stat_pub, &current_status, mavlink_fd);
-
- /* home position */
- orb_advert_t home_pub = -1;
- struct home_position_s home;
- memset(&home, 0, sizeof(home));
-
- if (stat_pub < 0) {
- warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
- warnx("exiting.");
- exit(ERROR);
- }
-
- mavlink_log_info(mavlink_fd, "system is running");
-
- /* create pthreads */
- pthread_attr_t subsystem_info_attr;
- pthread_attr_init(&subsystem_info_attr);
- pthread_attr_setstacksize(&subsystem_info_attr, 2048);
- pthread_create(&subsystem_info_thread, &subsystem_info_attr, orb_receive_loop, &current_status);
-
- /* Start monitoring loop */
- uint16_t counter = 0;
- uint8_t flight_env;
-
- /* Initialize to 0.0V */
- float battery_voltage = 0.0f;
- bool battery_voltage_valid = false;
- bool low_battery_voltage_actions_done = false;
- bool critical_battery_voltage_actions_done = false;
- uint8_t low_voltage_counter = 0;
- uint16_t critical_voltage_counter = 0;
- int16_t mode_switch_rc_value;
- float bat_remain = 1.0f;
-
- uint16_t stick_off_counter = 0;
- uint16_t stick_on_counter = 0;
-
- /* Subscribe to manual control data */
- int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- struct manual_control_setpoint_s sp_man;
- memset(&sp_man, 0, sizeof(sp_man));
-
- /* 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));
-
- 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));
- uint64_t last_global_position_time = 0;
-
- int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- struct vehicle_local_position_s local_position;
- memset(&local_position, 0, sizeof(local_position));
- uint64_t last_local_position_time = 0;
-
- /*
- * The home position is set based on GPS only, to prevent a dependency between
- * position estimator and commander. RAW GPS is more than good enough for a
- * non-flying vehicle.
- */
- int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- struct vehicle_gps_position_s gps_position;
- memset(&gps_position, 0, sizeof(gps_position));
-
- int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s sensors;
- memset(&sensors, 0, sizeof(sensors));
-
- int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s diff_pres;
- memset(&diff_pres, 0, sizeof(diff_pres));
- uint64_t last_diff_pres_time = 0;
-
- /* Subscribe to command topic */
- int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
- struct vehicle_command_s cmd;
- memset(&cmd, 0, sizeof(cmd));
-
- /* Subscribe to parameters changed topic */
- int param_changed_sub = orb_subscribe(ORB_ID(parameter_update));
- struct parameter_update_s param_changed;
- memset(&param_changed, 0, sizeof(param_changed));
-
- /* subscribe to battery topic */
- int battery_sub = orb_subscribe(ORB_ID(battery_status));
- struct battery_status_s battery;
- memset(&battery, 0, sizeof(battery));
- battery.voltage_v = 0.0f;
-
- // uint8_t vehicle_state_previous = current_status.state_machine;
- float voltage_previous = 0.0f;
-
- uint64_t last_idle_time = 0;
-
- /* now initialized */
- commander_initialized = true;
- thread_running = true;
-
- uint64_t start_time = hrt_absolute_time();
- uint64_t failsave_ll_start_time = 0;
-
- enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode;
- bool state_changed = true;
- bool param_init_forced = true;
-
- while (!thread_should_exit) {
-
- /* Get current values */
- bool new_data;
- orb_check(sp_man_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man);
- }
-
- orb_check(sp_offboard_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
- }
-
- orb_check(sensor_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
- }
-
- orb_check(diff_pres_sub, &new_data);
-
- if (new_data) {
- orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- last_diff_pres_time = diff_pres.timestamp;
- }
-
- orb_check(cmd_sub, &new_data);
-
- if (new_data) {
- /* got command */
- orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
-
- /* handle it */
- handle_command(stat_pub, &current_status, &cmd);
- }
-
- /* update parameters */
- orb_check(param_changed_sub, &new_data);
-
- if (new_data || param_init_forced) {
- param_init_forced = false;
- /* parameters changed */
- orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
-
-
- /* update parameters */
- if (!current_status.flag_system_armed) {
- if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
- warnx("failed setting new system type");
- }
-
- /* disable manual override for all systems that rely on electronic stabilization */
- if (current_status.system_type == VEHICLE_TYPE_QUADROTOR ||
- current_status.system_type == VEHICLE_TYPE_HEXAROTOR ||
- current_status.system_type == VEHICLE_TYPE_OCTOROTOR) {
- current_status.flag_external_manual_override_ok = false;
-
- } else {
- current_status.flag_external_manual_override_ok = true;
- }
-
- /* check and update system / component ID */
- param_get(_param_system_id, &(current_status.system_id));
- param_get(_param_component_id, &(current_status.component_id));
-
- }
- }
-
- /* update global position estimate */
- orb_check(global_position_sub, &new_data);
-
- if (new_data) {
- /* position changed */
- orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position);
- last_global_position_time = global_position.timestamp;
- }
-
- /* update local position estimate */
- orb_check(local_position_sub, &new_data);
-
- if (new_data) {
- /* position changed */
- orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
- last_local_position_time = local_position.timestamp;
- }
-
- /* update battery status */
- orb_check(battery_sub, &new_data);
- if (new_data) {
- orb_copy(ORB_ID(battery_status), battery_sub, &battery);
- battery_voltage = battery.voltage_v;
- battery_voltage_valid = true;
-
- /*
- * Only update battery voltage estimate if system has
- * been running for two and a half seconds.
- */
- if (hrt_absolute_time() - start_time > 2500000) {
- bat_remain = battery_remaining_estimate_voltage(battery_voltage);
- }
- }
-
- /* Slow but important 8 Hz checks */
- if (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 8) == 0) {
- /* toggle activity (blue) led at 1 Hz in standby, 10 Hz in armed mode */
- if ((current_status.state_machine == SYSTEM_STATE_GROUND_READY ||
- current_status.state_machine == SYSTEM_STATE_AUTO ||
- current_status.state_machine == SYSTEM_STATE_MANUAL)) {
- /* armed, solid */
- led_on(LED_AMBER);
-
- } else if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* not armed */
- led_toggle(LED_AMBER);
- }
-
- if (hrt_absolute_time() - gps_position.timestamp_position < 2000000) {
-
- /* toggle GPS (blue) led at 1 Hz if GPS present but no lock, make is solid once locked */
- if ((hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && (gps_position.fix_type == GPS_FIX_TYPE_3D)) {
- /* GPS lock */
- led_on(LED_BLUE);
-
- } else if ((counter + 4) % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
- /* no GPS lock, but GPS module is aquiring lock */
- led_toggle(LED_BLUE);
- }
-
- } else {
- /* no GPS info, don't light the blue led */
- led_off(LED_BLUE);
- }
-
- /* toggle GPS led at 5 Hz in HIL mode */
- if (current_status.flag_hil_enabled) {
- /* hil enabled */
- led_toggle(LED_BLUE);
-
- } else if (bat_remain < 0.3f && (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT)) {
- /* toggle arming (red) at 5 Hz on low battery or error */
- led_toggle(LED_AMBER);
-
- } else {
- // /* Constant error indication in standby mode without GPS */
- // if (!current_status.gps_valid) {
- // led_on(LED_AMBER);
-
- // } else {
- // led_off(LED_AMBER);
- // }
- }
-
- 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)
- current_status.load = 1000 - (interval_runtime / 1000); //system load is time spent in non-idle
-
- last_idle_time = system_load.tasks[0].total_runtime;
- }
- }
-
- // // XXX Export patterns and threshold to parameters
- /* Trigger audio event for low battery */
- if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 0)) {
- /* For less than 10%, start be really annoying at 5 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- ioctl(buzzer, TONE_SET_ALARM, 3);
-
- } else if (bat_remain < 0.1f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 4) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
-
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 0)) {
- /* For less than 20%, start be slightly annoying at 1 Hz */
- ioctl(buzzer, TONE_SET_ALARM, 0);
- tune_confirm();
-
- } else if (bat_remain < 0.2f && battery_voltage_valid && (counter % ((1000000 / COMMANDER_MONITORING_INTERVAL) / 2) == 2)) {
- ioctl(buzzer, TONE_SET_ALARM, 0);
- }
-
- /* Check battery voltage */
- /* write to sys_status */
- if (battery_voltage_valid) {
- current_status.voltage_battery = battery_voltage;
-
- } else {
- current_status.voltage_battery = 0.0f;
- }
-
- /* if battery voltage is getting lower, warn using buzzer, etc. */
- if (battery_voltage_valid && (bat_remain < 0.15f /* XXX MAGIC NUMBER */) && (false == low_battery_voltage_actions_done)) { //TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
-
- if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) {
- low_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "[cmd] WARNING! LOW BATTERY!");
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_WARNING;
- }
-
- low_voltage_counter++;
- }
-
- /* Critical, this is rather an emergency, kill signal to sdlog and change state machine */
- else if (battery_voltage_valid && (bat_remain < 0.1f /* XXX MAGIC NUMBER */) && (false == critical_battery_voltage_actions_done && true == low_battery_voltage_actions_done)) {
- if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) {
- critical_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY! CRITICAL BATTERY!");
- current_status.battery_warning = VEHICLE_BATTERY_WARNING_ALERT;
- state_machine_emergency(stat_pub, &current_status, mavlink_fd);
- }
-
- critical_voltage_counter++;
-
- } else {
- low_voltage_counter = 0;
- critical_voltage_counter = 0;
- }
-
- /* End battery voltage check */
-
-
- /*
- * Check for valid position information.
- *
- * If the system has a valid position source from an onboard
- * position estimator, it is safe to operate it autonomously.
- * The flag_vector_flight_mode_ok flag indicates that a minimum
- * set of position measurements is available.
- */
-
- /* store current state to reason later about a state change */
- bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
- bool global_pos_valid = current_status.flag_global_position_valid;
- bool local_pos_valid = current_status.flag_local_position_valid;
- bool airspeed_valid = current_status.flag_airspeed_valid;
-
- /* check for global or local position updates, set a timeout of 2s */
- if (hrt_absolute_time() - last_global_position_time < 2000000) {
- current_status.flag_global_position_valid = true;
- // XXX check for controller status and home position as well
-
- } else {
- current_status.flag_global_position_valid = false;
- }
-
- if (hrt_absolute_time() - last_local_position_time < 2000000) {
- current_status.flag_local_position_valid = true;
- // XXX check for controller status and home position as well
-
- } else {
- current_status.flag_local_position_valid = false;
- }
-
- /* Check for valid airspeed/differential pressure measurements */
- if (hrt_absolute_time() - last_diff_pres_time < 2000000) {
- current_status.flag_airspeed_valid = true;
-
- } else {
- current_status.flag_airspeed_valid = false;
- }
-
- /*
- * Consolidate global position and local position valid flags
- * for vector flight mode.
- */
- if (current_status.flag_local_position_valid ||
- current_status.flag_global_position_valid) {
- current_status.flag_vector_flight_mode_ok = true;
-
- } else {
- current_status.flag_vector_flight_mode_ok = false;
- }
-
- /* consolidate state change, flag as changed if required */
- if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok ||
- global_pos_valid != current_status.flag_global_position_valid ||
- local_pos_valid != current_status.flag_local_position_valid ||
- airspeed_valid != current_status.flag_airspeed_valid) {
- state_changed = true;
- }
-
- /*
- * Mark the position of the first position lock as return to launch (RTL)
- * position. The MAV will return here on command or emergency.
- *
- * Conditions:
- *
- * 1) The system aquired position lock just now
- * 2) The system has not aquired position lock before
- * 3) The system is not armed (on the ground)
- */
- if (!current_status.flag_valid_launch_position &&
- !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
- !current_status.flag_system_armed) {
- /* first time a valid position, store it and emit it */
-
- // XXX implement storage and publication of RTL position
- current_status.flag_valid_launch_position = true;
- current_status.flag_auto_flight_mode_ok = true;
- state_changed = true;
- }
-
- if (orb_check(ORB_ID(vehicle_gps_position), &new_data)) {
-
- orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
-
- /* check for first, long-term and valid GPS lock -> set home position */
- float hdop_m = gps_position.eph_m;
- float vdop_m = gps_position.epv_m;
-
- /* check if gps fix is ok */
- // XXX magic number
- 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 (gps_position.fix_type == GPS_FIX_TYPE_3D
- && (hdop_m < hdop_threshold_m)
- && (vdop_m < vdop_threshold_m)
- && !home_position_set
- && (hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && !current_status.flag_system_armed) {
- warnx("setting home position");
-
- /* copy position data to uORB home message, store it locally as well */
- 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;
-
- /* 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 */
- home_position_set = true;
- tune_confirm();
- }
- }
-
- /* ignore RC signals if in offboard control mode */
- if (!current_status.offboard_control_signal_found_once && sp_man.timestamp != 0) {
- /* Start RC state check */
-
- if ((hrt_absolute_time() - sp_man.timestamp) < 100000) {
-
- // /*
- // * Check if manual control modes have to be switched
- // */
- // if (!isfinite(sp_man.manual_mode_switch)) {
- // warnx("man mode sw not finite\n");
-
- // /* this switch is not properly mapped, set default */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
-
- // /* assuming a fixed wing, fall back to direct pass-through */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
-
- // } else if (sp_man.manual_mode_switch < -STICK_ON_OFF_LIMIT) {
-
- // /* bottom stick position, set direct mode for vehicles supporting it */
- // if ((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- // (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- // /* assuming a rotary wing, fall back to SAS */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
- // } else {
-
- // /* assuming a fixed wing, set to direct pass-through as requested */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = false;
- // }
-
- // } else if (sp_man.manual_mode_switch > STICK_ON_OFF_LIMIT) {
-
- // /* top stick position, set SAS for all vehicle types */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- // current_status.flag_control_attitude_enabled = true;
- // current_status.flag_control_rates_enabled = true;
-
- // } else {
- // /* center stick position, set rate control */
- // current_status.manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_RATES;
- // current_status.flag_control_attitude_enabled = false;
- // current_status.flag_control_rates_enabled = true;
- // }
-
- // warnx("man ctrl mode: %d\n", (int)current_status.manual_control_mode);
-
- /*
- * Check if manual stability control modes have to be switched
- */
- if (!isfinite(sp_man.manual_sas_switch)) {
-
- /* this switch is not properly mapped, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
-
- } else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) {
-
- /* bottom stick position, set default */
- /* this MUST be mapped to extremal position to switch easy in case of emergency */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
-
- } else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) {
-
- /* top stick position */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE;
-
- } else {
- /* center stick position, set altitude hold */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
- }
-
- if (current_status.manual_sas_mode != manual_sas_mode) {
- /* publish SAS mode changes immediately */
- manual_sas_mode = current_status.manual_sas_mode;
- state_changed = true;
- }
-
- /*
- * Check if left stick is in lower left position --> switch to standby state.
- * Do this only for multirotors, not for fixed wing aircraft.
- */
- if (((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status.system_type == VEHICLE_TYPE_OCTOROTOR)
- ) &&
- current_status.flag_control_manual_enabled &&
- current_status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS &&
- sp_man.yaw < -STICK_ON_OFF_LIMIT &&
- sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
- if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
- stick_on_counter = 0;
-
- } else {
- stick_off_counter++;
- stick_on_counter = 0;
- }
- }
-
- /* check if left stick is in lower right position --> arm */
- if (current_status.flag_control_manual_enabled &&
- current_status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS &&
- sp_man.yaw > STICK_ON_OFF_LIMIT &&
- sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
- if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
- stick_on_counter = 0;
-
- } else {
- stick_on_counter++;
- stick_off_counter = 0;
- }
- }
-
- /* check manual override switch - switch to manual or auto mode */
- if (sp_man.manual_override_switch > STICK_ON_OFF_LIMIT) {
- /* enable manual override */
- update_state_machine_mode_manual(stat_pub, &current_status, mavlink_fd);
-
- } else if (sp_man.manual_override_switch < -STICK_ON_OFF_LIMIT) {
- // /* check auto mode switch for correct mode */
- // if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) {
- // /* enable guided mode */
- // update_state_machine_mode_guided(stat_pub, &current_status, mavlink_fd);
-
- // } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) {
- // XXX hardcode to auto for now
- update_state_machine_mode_auto(stat_pub, &current_status, mavlink_fd);
-
- // }
-
- } else {
- /* center stick position, set SAS for all vehicle types */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
- }
-
- /* handle the case where RC signal was regained */
- if (!current_status.rc_signal_found_once) {
- current_status.rc_signal_found_once = true;
- mavlink_log_critical(mavlink_fd, "DETECTED RC SIGNAL FIRST TIME.");
-
- } else {
- if (current_status.rc_signal_lost) mavlink_log_critical(mavlink_fd, "[cmd] RECOVERY - RC SIGNAL GAINED!");
- }
-
- current_status.rc_signal_cutting_off = false;
- current_status.rc_signal_lost = false;
- current_status.rc_signal_lost_interval = 0;
-
- } else {
- static uint64_t last_print_time = 0;
-
- /* print error message for first RC glitch and then every 5 s / 5000 ms) */
- if (!current_status.rc_signal_cutting_off || ((hrt_absolute_time() - last_print_time) > 5000000)) {
- /* only complain if the offboard control is NOT active */
- current_status.rc_signal_cutting_off = true;
- mavlink_log_critical(mavlink_fd, "CRITICAL - NO REMOTE SIGNAL!");
- last_print_time = hrt_absolute_time();
- }
-
- /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
- current_status.rc_signal_lost_interval = hrt_absolute_time() - sp_man.timestamp;
-
- /* if the RC signal is gone for a full second, consider it lost */
- if (current_status.rc_signal_lost_interval > 1000000) {
- current_status.rc_signal_lost = true;
- current_status.failsave_lowlevel = true;
- state_changed = true;
- }
-
- // if (hrt_absolute_time() - current_status.failsave_ll_start_time > failsafe_lowlevel_timeout_ms*1000) {
- // publish_armed_status(&current_status);
- // }
- }
- }
-
-
-
-
- /* End mode switch */
-
- /* END RC state check */
-
-
- /* State machine update for offboard control */
- if (!current_status.rc_signal_found_once && sp_offboard.timestamp != 0) {
- if ((hrt_absolute_time() - sp_offboard.timestamp) < 5000000) {
-
- /* decide about attitude control flag, enable in att/pos/vel */
- bool attitude_ctrl_enabled = (sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY ||
- sp_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION);
-
- /* decide about rate control flag, enable it always XXX (for now) */
- bool rates_ctrl_enabled = true;
-
- /* set up control mode */
- if (current_status.flag_control_attitude_enabled != attitude_ctrl_enabled) {
- current_status.flag_control_attitude_enabled = attitude_ctrl_enabled;
- state_changed = true;
- }
-
- if (current_status.flag_control_rates_enabled != rates_ctrl_enabled) {
- current_status.flag_control_rates_enabled = rates_ctrl_enabled;
- state_changed = true;
- }
-
- /* handle the case where offboard control signal was regained */
- if (!current_status.offboard_control_signal_found_once) {
- current_status.offboard_control_signal_found_once = true;
- /* enable offboard control, disable manual input */
- current_status.flag_control_manual_enabled = false;
- current_status.flag_control_offboard_enabled = true;
- state_changed = true;
- tune_confirm();
-
- mavlink_log_critical(mavlink_fd, "DETECTED OFFBOARD SIGNAL FIRST");
-
- } else {
- if (current_status.offboard_control_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RECOVERY OFFBOARD CONTROL");
- state_changed = true;
- tune_confirm();
- }
- }
-
- current_status.offboard_control_signal_weak = false;
- current_status.offboard_control_signal_lost = false;
- current_status.offboard_control_signal_lost_interval = 0;
-
- /* arm / disarm on request */
- if (sp_offboard.armed && !current_status.flag_system_armed) {
- update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
- /* switch to stabilized mode = takeoff */
- update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
-
- } else if (!sp_offboard.armed && current_status.flag_system_armed) {
- update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
- }
-
- } else {
- static uint64_t last_print_time = 0;
-
- /* print error message for first RC glitch and then every 5 s / 5000 ms) */
- if (!current_status.offboard_control_signal_weak || ((hrt_absolute_time() - last_print_time) > 5000000)) {
- current_status.offboard_control_signal_weak = true;
- mavlink_log_critical(mavlink_fd, "CRIT:NO OFFBOARD CONTROL!");
- last_print_time = hrt_absolute_time();
- }
-
- /* flag as lost and update interval since when the signal was lost (to initiate RTL after some time) */
- current_status.offboard_control_signal_lost_interval = hrt_absolute_time() - sp_offboard.timestamp;
-
- /* if the signal is gone for 0.1 seconds, consider it lost */
- if (current_status.offboard_control_signal_lost_interval > 100000) {
- current_status.offboard_control_signal_lost = true;
- current_status.failsave_lowlevel_start_time = hrt_absolute_time();
- tune_confirm();
-
- /* kill motors after timeout */
- if (hrt_absolute_time() - current_status.failsave_lowlevel_start_time > failsafe_lowlevel_timeout_ms * 1000) {
- current_status.failsave_lowlevel = true;
- state_changed = true;
- }
- }
- }
- }
-
-
- current_status.counter++;
- current_status.timestamp = hrt_absolute_time();
-
-
- /* If full run came back clean, transition to standby */
- if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT &&
- current_status.flag_preflight_gyro_calibration == false &&
- current_status.flag_preflight_mag_calibration == false &&
- current_status.flag_preflight_accel_calibration == false) {
- /* All ok, no calibration going on, go to standby */
- do_state_update(stat_pub, &current_status, mavlink_fd, SYSTEM_STATE_STANDBY);
- }
-
- /* publish at least with 1 Hz */
- if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 || state_changed) {
- publish_armed_status(&current_status);
- orb_publish(ORB_ID(vehicle_status), stat_pub, &current_status);
- state_changed = false;
- }
-
- /* Store old modes to detect and act on state transitions */
- voltage_previous = current_status.voltage_battery;
-
- fflush(stdout);
- counter++;
- usleep(COMMANDER_MONITORING_INTERVAL);
- }
-
- /* wait for threads to complete */
- // pthread_join(command_handling_thread, NULL);
- pthread_join(subsystem_info_thread, NULL);
-
- /* close fds */
- led_deinit();
- buzzer_deinit();
- close(sp_man_sub);
- close(sp_offboard_sub);
- close(global_position_sub);
- close(sensor_sub);
- close(cmd_sub);
-
- warnx("exiting..\n");
- fflush(stdout);
-
- thread_running = false;
-
- return 0;
-}
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
new file mode 100644
index 000000000..a548f943e
--- /dev/null
+++ b/src/modules/commander/commander.cpp
@@ -0,0 +1,1793 @@
+/****************************************************************************
+ *
+ * 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>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file commander.cpp
+ * Main system state machine implementation.
+ *
+ */
+
+#include <nuttx/config.h>
+#include <pthread.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+#include <sys/prctl.h>
+#include <sys/stat.h>
+#include <string.h>
+#include <math.h>
+#include <poll.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/offboard_control_setpoint.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_local_position.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 <drivers/drv_led.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <systemlib/cpuload.h>
+#include <systemlib/rc_check.h>
+
+#include "px4_custom_mode.h"
+#include "commander_helper.h"
+#include "state_machine_helper.h"
+#include "calibration_routines.h"
+#include "accelerometer_calibration.h"
+#include "gyro_calibration.h"
+#include "mag_calibration.h"
+#include "baro_calibration.h"
+#include "rc_calibration.h"
+#include "airspeed_calibration.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+extern struct system_load_s system_load;
+
+#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
+#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
+
+/* Decouple update interval and hysteris counters, all depends on intervals */
+#define COMMANDER_MONITORING_INTERVAL 50000
+#define COMMANDER_MONITORING_LOOPSPERMSEC (1/(COMMANDER_MONITORING_INTERVAL/1000.0f))
+#define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
+#define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
+
+#define STICK_ON_OFF_LIMIT 0.75f
+#define STICK_THRUST_RANGE 1.0f
+#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 PRINT_INTERVAL 5000000
+#define PRINT_MODE_REJECT_INTERVAL 2000000
+
+enum MAV_MODE_FLAG {
+ MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1, /* 0b00000001 Reserved for future use. | */
+ MAV_MODE_FLAG_TEST_ENABLED = 2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
+ MAV_MODE_FLAG_AUTO_ENABLED = 4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
+ MAV_MODE_FLAG_GUIDED_ENABLED = 8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
+ MAV_MODE_FLAG_STABILIZE_ENABLED = 16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
+ MAV_MODE_FLAG_HIL_ENABLED = 32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
+ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64, /* 0b01000000 remote control input is enabled. | */
+ MAV_MODE_FLAG_SAFETY_ARMED = 128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
+ MAV_MODE_FLAG_ENUM_END = 129, /* | */
+};
+
+/* Mavlink file descriptors */
+static int mavlink_fd;
+
+/* flags */
+static bool commander_initialized = false;
+static bool thread_should_exit = false; /**< daemon exit flag */
+static bool thread_running = false; /**< daemon status flag */
+static int daemon_task; /**< Handle of daemon task / thread */
+
+static unsigned int leds_counter;
+/* To remember when last notification was sent */
+static uint64_t last_print_mode_reject_time = 0;
+/* if connected via USB */
+static bool on_usb_power = false;
+
+
+/* tasks waiting for low prio thread */
+typedef enum {
+ LOW_PRIO_TASK_NONE = 0,
+ LOW_PRIO_TASK_PARAM_SAVE,
+ LOW_PRIO_TASK_PARAM_LOAD,
+ LOW_PRIO_TASK_GYRO_CALIBRATION,
+ LOW_PRIO_TASK_MAG_CALIBRATION,
+ LOW_PRIO_TASK_ALTITUDE_CALIBRATION,
+ LOW_PRIO_TASK_RC_CALIBRATION,
+ LOW_PRIO_TASK_ACCEL_CALIBRATION,
+ LOW_PRIO_TASK_AIRSPEED_CALIBRATION
+} low_prio_task_t;
+
+static low_prio_task_t low_prio_task = LOW_PRIO_TASK_NONE;
+
+/**
+ * The daemon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int commander_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+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);
+
+/**
+ * Mainloop of commander.
+ */
+int commander_thread_main(int argc, char *argv[]);
+
+void toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed);
+
+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);
+
+transition_result_t check_main_state_machine(struct vehicle_status_s *current_status);
+
+void print_reject_mode(const char *msg);
+
+void print_reject_arm(const char *msg);
+
+void print_status();
+
+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);
+
+/**
+ * Loop that runs at a lower rate and priority for calibration and parameter tasks.
+ */
+void *commander_low_prio_loop(void *arg);
+
+void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result);
+
+
+int commander_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("commander already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ daemon_task = task_spawn_cmd("commander",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 40,
+ 3000,
+ commander_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("\tcommander is running\n");
+ print_status();
+
+ } else {
+ warnx("\tcommander not started\n");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+void usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
+ exit(1);
+}
+
+void print_status()
+{
+ warnx("usb powered: %s", (on_usb_power) ? "yes" : "no");
+
+ /* read all relevant states */
+ int state_sub = orb_subscribe(ORB_ID(vehicle_status));
+ struct vehicle_status_s state;
+ orb_copy(ORB_ID(vehicle_status), state_sub, &state);
+
+ const char *armed_str;
+
+ switch (state.arming_state) {
+ case ARMING_STATE_INIT:
+ armed_str = "INIT";
+ break;
+
+ case ARMING_STATE_STANDBY:
+ armed_str = "STANDBY";
+ break;
+
+ case ARMING_STATE_ARMED:
+ armed_str = "ARMED";
+ break;
+
+ case ARMING_STATE_ARMED_ERROR:
+ armed_str = "ARMED_ERROR";
+ break;
+
+ case ARMING_STATE_STANDBY_ERROR:
+ armed_str = "STANDBY_ERROR";
+ break;
+
+ case ARMING_STATE_REBOOT:
+ armed_str = "REBOOT";
+ break;
+
+ case ARMING_STATE_IN_AIR_RESTORE:
+ armed_str = "IN_AIR_RESTORE";
+ break;
+
+ default:
+ armed_str = "ERR: UNKNOWN STATE";
+ break;
+ }
+
+
+ warnx("arming: %s", armed_str);
+}
+
+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)
+{
+ /* result of the command */
+ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+
+ /* only handle high-priority commands here */
+
+ /* 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;
+
+ // TODO remove debug code
+ //mavlink_log_critical(mavlink_fd, "[cmd] command setmode: %d %d", base_mode, custom_main_mode);
+ /* set arming state */
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by command");
+ }
+
+ } else {
+ if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ arming_state_t new_arming_state = (status->arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+ arming_res = arming_state_transition(status, safety, new_arming_state, armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] DISARMED by command");
+ }
+
+ } else {
+ arming_res = TRANSITION_NOT_CHANGED;
+ }
+ }
+
+ /* set main state */
+ transition_result_t main_res = TRANSITION_DENIED;
+
+ 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);
+
+ } 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_EASY) {
+ /* EASY */
+ main_res = main_state_transition(status, MAIN_STATE_EASY);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ }
+
+ } else {
+ /* use base mode */
+ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } 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);
+
+ } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
+ }
+ }
+
+ if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ break;
+ }
+
+ case VEHICLE_CMD_NAV_TAKEOFF: {
+ if (armed->armed) {
+ transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
+
+ if (nav_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
+ }
+
+ if (nav_res != TRANSITION_DENIED) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ } else {
+ /* reject TAKEOFF not armed */
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+
+ break;
+ }
+
+ case VEHICLE_CMD_COMPONENT_ARM_DISARM:
+ // XXX implement later
+ result = VEHICLE_CMD_RESULT_DENIED;
+ break;
+
+ default:
+ 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, "[cmd] command denied: %u", cmd->command);
+
+ } else if (result == VEHICLE_CMD_RESULT_FAILED) {
+ mavlink_log_critical(mavlink_fd, "[cmd] command failed: %u", cmd->command);
+
+ } else if (result == VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED) {
+ mavlink_log_critical(mavlink_fd, "[cmd] command temporarily rejected: %u", cmd->command);
+
+ }
+ }
+
+ /* send any requested ACKs */
+ if (cmd->confirmation > 0 && result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ /* send acknowledge command */
+ // XXX TODO
+ }
+
+}
+
+static struct vehicle_status_s status;
+
+/* armed topic */
+static struct actuator_armed_s armed;
+
+static struct safety_s safety;
+
+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;
+
+ /* 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");
+
+ /* welcome user */
+ warnx("[commander] starting");
+
+ /* pthread for slow low prio thread */
+ pthread_t commander_low_prio_thread;
+
+ /* initialize */
+ if (led_init() != 0) {
+ warnx("ERROR: Failed to initialize leds");
+ }
+
+ if (buzzer_init() != OK) {
+ warnx("ERROR: Failed to initialize buzzer");
+ }
+
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ if (mavlink_fd < 0) {
+ /* try again later */
+ usleep(20000);
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ if (mavlink_fd < 0) {
+ warnx("ERROR: Failed to open MAVLink log stream again, start mavlink app first.");
+ }
+ }
+
+ /* Main state machine */
+ orb_advert_t status_pub;
+ /* make sure we are in preflight state */
+ memset(&status, 0, sizeof(status));
+ status.condition_landed = true; // initialize to safe value
+
+ /* armed topic */
+ orb_advert_t armed_pub;
+ /* Initialize armed with all false */
+ memset(&armed, 0, sizeof(armed));
+
+ /* flags for control apps */
+ struct vehicle_control_mode_s control_mode;
+ orb_advert_t control_mode_pub;
+
+ /* 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.arming_state = ARMING_STATE_INIT;
+ status.hil_state = HIL_STATE_OFF;
+
+ /* neither manual nor offboard control commands have been received */
+ status.offboard_control_signal_found_once = false;
+ status.rc_signal_found_once = false;
+
+ /* 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;
+
+ /* set battery warning flag */
+ status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
+ status.condition_battery_voltage_valid = false;
+
+ // 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;
+
+ /* advertise to ORB */
+ status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+ /* publish current state machine */
+
+ /* publish initial state */
+ status.counter++;
+ status.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+
+ armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
+
+ control_mode_pub = orb_advertise(ORB_ID(vehicle_control_mode), &control_mode);
+
+ /* 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);
+ }
+
+ mavlink_log_info(mavlink_fd, "[cmd] started");
+
+ pthread_attr_t commander_low_prio_attr;
+ pthread_attr_init(&commander_low_prio_attr);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2048);
+
+ struct sched_param param;
+ /* low priority */
+ param.sched_priority = SCHED_PRIORITY_DEFAULT - 50;
+ (void)pthread_attr_setschedparam(&commander_low_prio_attr, &param);
+ pthread_create(&commander_low_prio_thread, &commander_low_prio_attr, commander_low_prio_loop, NULL);
+
+ /* Start monitoring loop */
+ unsigned counter = 0;
+ unsigned low_voltage_counter = 0;
+ unsigned critical_voltage_counter = 0;
+ unsigned stick_off_counter = 0;
+ unsigned stick_on_counter = 0;
+
+ 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;
+
+ bool status_changed = true;
+ bool param_init_forced = true;
+
+ bool updated = false;
+
+ bool rc_calibration_ok = (OK == rc_calibration_check());
+
+ /* Subscribe to safety topic */
+ int safety_sub = orb_subscribe(ORB_ID(safety));
+ memset(&safety, 0, sizeof(safety));
+ safety.safety_switch_available = false;
+ safety.safety_off = false;
+
+ /* Subscribe to manual control data */
+ int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ struct manual_control_setpoint_s sp_man;
+ memset(&sp_man, 0, sizeof(sp_man));
+
+ /* 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 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));
+
+ /* Subscribe to local position data */
+ int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ struct vehicle_local_position_s local_position;
+ memset(&local_position, 0, sizeof(local_position));
+
+ /*
+ * The home position is set based on GPS only, to prevent a dependency between
+ * position estimator and commander. RAW GPS is more than good enough for a
+ * non-flying vehicle.
+ */
+
+ /* Subscribe to GPS topic */
+ int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ struct vehicle_gps_position_s gps_position;
+ memset(&gps_position, 0, sizeof(gps_position));
+
+ /* Subscribe to sensor topic */
+ int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ struct sensor_combined_s sensors;
+ memset(&sensors, 0, sizeof(sensors));
+
+ /* Subscribe to differential pressure topic */
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
+ memset(&diff_pres, 0, sizeof(diff_pres));
+
+ /* Subscribe to command topic */
+ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ struct vehicle_command_s cmd;
+ memset(&cmd, 0, sizeof(cmd));
+
+ /* Subscribe to parameters changed topic */
+ int param_changed_sub = orb_subscribe(ORB_ID(parameter_update));
+ struct parameter_update_s param_changed;
+ memset(&param_changed, 0, sizeof(param_changed));
+
+ /* Subscribe to battery topic */
+ int battery_sub = orb_subscribe(ORB_ID(battery_status));
+ struct battery_status_s battery;
+ memset(&battery, 0, sizeof(battery));
+ battery.voltage_v = 0.0f;
+
+ /* Subscribe to subsystem info topic */
+ int subsys_sub = orb_subscribe(ORB_ID(subsystem_info));
+ struct subsystem_info_s info;
+ memset(&info, 0, sizeof(info));
+
+ /* now initialized */
+ commander_initialized = true;
+ thread_running = true;
+
+ start_time = hrt_absolute_time();
+
+ while (!thread_should_exit) {
+
+ /* update parameters */
+ orb_check(param_changed_sub, &updated);
+
+ if (updated || param_init_forced) {
+ param_init_forced = false;
+ /* parameters changed */
+ orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
+
+ /* update parameters */
+ if (!armed.armed) {
+ if (param_get(_param_sys_type, &(status.system_type)) != OK) {
+ warnx("failed getting new system type");
+ }
+
+ /* disable manual override for all systems that rely on electronic stabilization */
+ if (status.system_type == VEHICLE_TYPE_COAXIAL ||
+ status.system_type == VEHICLE_TYPE_HELICOPTER ||
+ status.system_type == VEHICLE_TYPE_TRICOPTER ||
+ 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_changed = true;
+
+ /* Re-check RC calibration */
+ rc_calibration_ok = (OK == rc_calibration_check());
+ }
+ }
+
+ orb_check(sp_man_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man);
+ }
+
+ orb_check(sp_offboard_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
+ }
+
+ orb_check(sensor_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
+ }
+
+ orb_check(diff_pres_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ }
+
+ check_valid(diff_pres.timestamp, DIFFPRESS_TIMEOUT, true, &(status.condition_airspeed_valid), &status_changed);
+
+ orb_check(cmd_sub, &updated);
+
+ if (updated) {
+ /* got command */
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+
+ /* handle it */
+ handle_command(&status, &safety, &control_mode, &cmd, &armed);
+ }
+
+ /* update safety topic */
+ orb_check(safety_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(safety), safety_sub, &safety);
+ }
+
+ /* update global position estimate */
+ orb_check(global_position_sub, &updated);
+
+ if (updated) {
+ /* position changed */
+ 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);
+
+ if (updated) {
+ /* position changed */
+ orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
+ }
+
+ /* 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);
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
+
+ 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, "[cmd] LANDED");
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "[cmd] IN AIR");
+ }
+ }
+ }
+
+ /* update battery status */
+ orb_check(battery_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(battery_status), battery_sub, &battery);
+
+ // warnx("bat v: %2.2f", battery.voltage_v);
+
+ /* only consider battery voltage if system has been running 2s and battery voltage is not 0 */
+ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_v > 0.001f) {
+ status.battery_voltage = battery.voltage_v;
+ status.condition_battery_voltage_valid = true;
+ status.battery_remaining = battery_remaining_estimate_voltage(status.battery_voltage);
+ }
+ }
+
+ /* update subsystem */
+ orb_check(subsys_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(subsystem_info), subsys_sub, &info);
+
+ warnx("subsystem changed: %d\n", (int)info.subsystem_type);
+
+ /* mark / unmark as present */
+ if (info.present) {
+ status.onboard_control_sensors_present |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_present &= ~info.subsystem_type;
+ }
+
+ /* mark / unmark as enabled */
+ if (info.enabled) {
+ status.onboard_control_sensors_enabled |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_enabled &= ~info.subsystem_type;
+ }
+
+ /* mark / unmark as ok */
+ if (info.ok) {
+ status.onboard_control_sensors_health |= info.subsystem_type;
+
+ } else {
+ status.onboard_control_sensors_health &= ~info.subsystem_type;
+ }
+
+ status_changed = true;
+ }
+
+ 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
+
+ last_idle_time = system_load.tasks[0].total_runtime;
+
+ /* check if board is connected via USB */
+ struct stat statbuf;
+ //on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
+ }
+
+ // XXX remove later
+ //warnx("bat remaining: %2.2f", status.battery_remaining);
+
+ /* 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) {
+ //TODO: add filter, or call emergency after n measurements < VOLTAGE_BATTERY_MINIMAL_MILLIVOLTS
+ if (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT) {
+ low_battery_voltage_actions_done = true;
+ mavlink_log_critical(mavlink_fd, "[cmd] WARNING: LOW BATTERY");
+ status.battery_warning = VEHICLE_BATTERY_WARNING_WARNING;
+ status_changed = true;
+ battery_tune_played = false;
+ }
+
+ low_voltage_counter++;
+
+ } 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 */
+ if (critical_voltage_counter > CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT) {
+ critical_battery_voltage_actions_done = true;
+ mavlink_log_critical(mavlink_fd, "[cmd] EMERGENCY: CRITICAL BATTERY");
+ status.battery_warning = VEHICLE_BATTERY_WARNING_ALERT;
+ battery_tune_played = false;
+
+ if (armed.armed) {
+ // XXX not sure what should happen when voltage is low in flight
+ //arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
+ } else {
+ // XXX should we still allow to arm with critical battery?
+ //arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
+ }
+
+ status_changed = true;
+ }
+
+ critical_voltage_counter++;
+
+ } else {
+ low_voltage_counter = 0;
+ critical_voltage_counter = 0;
+ }
+
+ /* End battery voltage check */
+
+ /* 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, ARMING_STATE_STANDBY, &armed);
+
+ } else {
+ // XXX: Add emergency stuff if sensors are lost
+ }
+
+
+ /*
+ * Check for valid position information.
+ *
+ * If the system has a valid position source from an onboard
+ * position estimator, it is safe to operate it autonomously.
+ * The flag_vector_flight_mode_ok flag indicates that a minimum
+ * set of position measurements is available.
+ */
+
+ orb_check(gps_sub, &updated);
+
+ 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);
+ }
+
+ /* mark home position as set */
+ home_position_set = true;
+ tune_positive();
+ }
+ }
+
+ /* ignore RC signals if in offboard control mode */
+ if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0) {
+ /* 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, "[cmd] detected RC signal first time");
+ status_changed = true;
+
+ } else {
+ if (status.rc_signal_lost) {
+ mavlink_log_critical(mavlink_fd, "[cmd] 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, new_arming_state, &armed);
+ stick_off_counter = 0;
+
+ } else {
+ stick_off_counter++;
+ }
+
+ } 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 &&
+ status.main_state == MAIN_STATE_MANUAL &&
+ sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
+ if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
+ res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ stick_on_counter = 0;
+
+ } else {
+ stick_on_counter++;
+ }
+
+ } else {
+ stick_on_counter = 0;
+ }
+
+ if (res == TRANSITION_CHANGED) {
+ if (status.arming_state == ARMING_STATE_ARMED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
+
+ } else {
+ mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
+ }
+
+ } else if (res == TRANSITION_DENIED) {
+ /* DENIED here indicates safety switch not pressed */
+
+ if (!(!safety.safety_switch_available || safety.safety_off)) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+
+ } else {
+ 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, "[cmd] ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ }
+ }
+
+ /* fill current_status according to mode switches */
+ check_mode_switches(&sp_man, &status);
+
+ /* evaluate the main state machine */
+ res = check_main_state_machine(&status);
+
+ if (res == TRANSITION_CHANGED) {
+ //mavlink_log_info(mavlink_fd, "[cmd] main state: %d", status.main_state);
+ tune_positive();
+
+ } 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, "[cmd] 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, "[cmd] CRITICAL: RC SIGNAL LOST");
+ status.rc_signal_lost = true;
+ status_changed = true;
+ }
+ }
+ }
+
+ /* evaluate the navigation state machine */
+ transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
+
+ 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, "[cmd] ERROR: nav denied: arm %d main %d nav %d", status.arming_state, status.main_state, status.navigation_state);
+ }
+
+ /* 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();
+
+ 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);
+ status_changed = true;
+
+ } else {
+ status_changed = false;
+ }
+
+ hrt_abstime t1 = hrt_absolute_time();
+
+ /* publish arming state */
+ if (arming_state_changed) {
+ armed.timestamp = t1;
+ orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
+ }
+
+ /* publish control mode */
+ if (navigation_state_changed || arming_state_changed) {
+ /* publish new navigation state */
+ control_mode.flag_armed = armed.armed; // copy armed state to vehicle_control_mode topic
+ control_mode.counter++;
+ control_mode.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
+ }
+
+ /* publish states (armed, control mode, vehicle status) at least with 5 Hz */
+ if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
+ status.counter++;
+ status.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_status), status_pub, &status);
+ control_mode.timestamp = t1;
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
+ armed.timestamp = t1;
+ orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
+ }
+
+ /* play arming and battery warning tunes */
+ if (!arm_tune_played && armed.armed) {
+ /* play tune when armed */
+ if (tune_arm() == OK)
+ arm_tune_played = true;
+
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
+ /* play tune on battery warning */
+ if (tune_low_bat() == OK)
+ battery_tune_played = true;
+
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
+ /* play tune on battery critical */
+ if (tune_critical_bat() == OK)
+ battery_tune_played = true;
+
+ } else if (battery_tune_played) {
+ tune_stop();
+ battery_tune_played = false;
+ }
+
+ /* reset arm_tune_played when disarmed */
+ if (!(armed.armed && (!safety.safety_switch_available || (safety.safety_off && safety.safety_switch_available)))) {
+ arm_tune_played = false;
+ }
+
+ fflush(stdout);
+ counter++;
+
+ toggle_status_leds(&status, &armed, arming_state_changed || status_changed);
+
+ usleep(COMMANDER_MONITORING_INTERVAL);
+ }
+
+ /* wait for threads to complete */
+ pthread_join(commander_low_prio_thread, NULL);
+
+ /* close fds */
+ led_deinit();
+ buzzer_deinit();
+ close(sp_man_sub);
+ close(sp_offboard_sub);
+ close(local_position_sub);
+ close(global_position_sub);
+ close(gps_sub);
+ close(sensor_sub);
+ close(safety_sub);
+ close(cmd_sub);
+ close(subsys_sub);
+ close(diff_pres_sub);
+ close(param_changed_sub);
+ close(battery_sub);
+
+ warnx("exiting");
+ fflush(stdout);
+
+ thread_running = false;
+
+ return 0;
+}
+
+void
+check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed)
+{
+ hrt_abstime t = hrt_absolute_time();
+ bool valid_new = (t < timestamp + timeout && t > timeout && valid_in);
+
+ if (*valid_out != valid_new) {
+ *valid_out = valid_new;
+ *changed = true;
+ }
+}
+
+void
+toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed)
+{
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
+ if (armed->armed) {
+ /* armed, solid */
+ led_on(LED_BLUE);
+
+ } else if (armed->ready_to_arm) {
+ /* ready to arm, blink at 1Hz */
+ if (leds_counter % 20 == 0)
+ led_toggle(LED_BLUE);
+
+ } else {
+ /* not ready to arm, blink at 10Hz */
+ if (leds_counter % 2 == 0)
+ led_toggle(LED_BLUE);
+ }
+
+#endif
+
+ if (changed) {
+
+ int i;
+ rgbled_pattern_t pattern;
+ memset(&pattern, 0, sizeof(pattern));
+
+ if (armed->armed) {
+ /* armed, solid */
+ if (status->battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
+ pattern.color[0] = (on_usb_power) ? RGBLED_COLOR_DIM_AMBER : RGBLED_COLOR_AMBER;
+
+ } else if (status->battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
+ pattern.color[0] = (on_usb_power) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED;
+
+ } else {
+ pattern.color[0] = (on_usb_power) ? RGBLED_COLOR_DIM_GREEN : RGBLED_COLOR_GREEN;
+ }
+
+ pattern.duration[0] = 1000;
+
+ } else if (armed->ready_to_arm) {
+ for (i = 0; i < 3; i++) {
+ if (status->battery_warning == VEHICLE_BATTERY_WARNING_WARNING) {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_AMBER : RGBLED_COLOR_AMBER;
+
+ } else if (status->battery_warning == VEHICLE_BATTERY_WARNING_ALERT) {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED;
+
+ } else {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_GREEN : RGBLED_COLOR_GREEN;
+ }
+
+ pattern.duration[i * 2] = 200;
+
+ pattern.color[i * 2 + 1] = RGBLED_COLOR_OFF;
+ pattern.duration[i * 2 + 1] = 800;
+ }
+
+ if (status->condition_global_position_valid) {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_BLUE : RGBLED_COLOR_BLUE;
+ pattern.duration[i * 2] = 1000;
+ pattern.color[i * 2 + 1] = RGBLED_COLOR_OFF;
+ pattern.duration[i * 2 + 1] = 800;
+
+ } else {
+ for (i = 3; i < 6; i++) {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_BLUE : RGBLED_COLOR_BLUE;
+ pattern.duration[i * 2] = 100;
+ pattern.color[i * 2 + 1] = RGBLED_COLOR_OFF;
+ pattern.duration[i * 2 + 1] = 100;
+ }
+
+ pattern.color[6 * 2] = RGBLED_COLOR_OFF;
+ pattern.duration[6 * 2] = 700;
+ }
+
+ } else {
+ for (i = 0; i < 3; i++) {
+ pattern.color[i * 2] = (on_usb_power) ? RGBLED_COLOR_DIM_RED : RGBLED_COLOR_RED;
+ pattern.duration[i * 2] = 200;
+ pattern.color[i * 2 + 1] = RGBLED_COLOR_OFF;
+ pattern.duration[i * 2 + 1] = 200;
+ }
+
+ /* not ready to arm, blink at 10Hz */
+ }
+
+ rgbled_set_pattern(&pattern);
+ }
+
+ /* give system warnings on error LED, XXX maybe add memory usage warning too */
+ if (status->load > 0.95f) {
+ if (leds_counter % 2 == 0)
+ led_toggle(LED_AMBER);
+
+ } else {
+ led_off(LED_AMBER);
+ }
+
+ leds_counter++;
+}
+
+void
+check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *current_status)
+{
+ /* main mode switch */
+ if (!isfinite(sp_man->mode_switch)) {
+ warnx("mode sw not finite");
+ current_status->mode_switch = MODE_SWITCH_MANUAL;
+
+ } else if (sp_man->mode_switch > STICK_ON_OFF_LIMIT) {
+ current_status->mode_switch = MODE_SWITCH_AUTO;
+
+ } else if (sp_man->mode_switch < -STICK_ON_OFF_LIMIT) {
+ current_status->mode_switch = MODE_SWITCH_MANUAL;
+
+ } else {
+ current_status->mode_switch = MODE_SWITCH_ASSISTED;
+ }
+
+ /* 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;
+
+ } else {
+ current_status->return_switch = RETURN_SWITCH_NONE;
+ }
+
+ /* assisted switch */
+ if (!isfinite(sp_man->assisted_switch)) {
+ current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
+
+ } else if (sp_man->assisted_switch > STICK_ON_OFF_LIMIT) {
+ current_status->assisted_switch = ASSISTED_SWITCH_EASY;
+
+ } else {
+ current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
+ }
+
+ /* mission switch */
+ if (!isfinite(sp_man->mission_switch)) {
+ current_status->mission_switch = MISSION_SWITCH_MISSION;
+
+ } else if (sp_man->mission_switch > STICK_ON_OFF_LIMIT) {
+ current_status->mission_switch = MISSION_SWITCH_NONE;
+
+ } else {
+ current_status->mission_switch = MISSION_SWITCH_MISSION;
+ }
+}
+
+transition_result_t
+check_main_state_machine(struct vehicle_status_s *current_status)
+{
+ /* evaluate the main state machine */
+ transition_result_t res = TRANSITION_DENIED;
+
+ switch (current_status->mode_switch) {
+ case MODE_SWITCH_MANUAL:
+ res = main_state_transition(current_status, 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);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
+
+ // else fallback to SEATBELT
+ print_reject_mode("EASY");
+ }
+
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this mode
+
+ if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
+ print_reject_mode("SEATBELT");
+
+ // else fallback to MANUAL
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
+
+ case MODE_SWITCH_AUTO:
+ res = main_state_transition(current_status, MAIN_STATE_AUTO);
+
+ 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("AUTO");
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+
+ 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);
+ // TRANSITION_DENIED is not possible here
+ break;
+
+ default:
+ break;
+ }
+
+ return res;
+}
+
+void
+print_reject_mode(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, "[cmd] WARNING: reject %s", msg);
+ mavlink_log_critical(mavlink_fd, s);
+ tune_negative();
+ }
+}
+
+void
+print_reject_arm(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, "[cmd] %s", msg);
+ mavlink_log_critical(mavlink_fd, s);
+ tune_negative();
+ }
+}
+
+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 res = TRANSITION_DENIED;
+
+ if (status->main_state == MAIN_STATE_AUTO) {
+ if (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ if (status->navigation_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
+ /* don't switch to other states until takeoff not completed */
+ if (local_pos->z > -5.0f || status->condition_landed) {
+ res = TRANSITION_NOT_CHANGED;
+ }
+ }
+
+ if (res != TRANSITION_NOT_CHANGED) {
+ /* check again, state can be changed */
+ if (status->condition_landed) {
+ /* if landed: transitions only to AUTO_READY are allowed */
+ res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode);
+ // TRANSITION_DENIED is not possible here
+
+ } else {
+ /* not landed */
+ 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 in air when no RC control */
+ 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) {
+ /* in air: try to hold position */
+ 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, "[cmd] FAILSAFE: POS HOLD");
+
+ } else {
+ if (status->condition_landed) {
+ mavlink_log_critical(mavlink_fd, "[cmd] FAILSAFE: ALT HOLD (LAND)");
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "[cmd] 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;
+
+ default:
+ break;
+ }
+ }
+ }
+
+ return res;
+}
+
+void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT result)
+{
+ switch (result) {
+ case VEHICLE_CMD_RESULT_ACCEPTED:
+ tune_positive();
+ break;
+
+ case VEHICLE_CMD_RESULT_DENIED:
+ mavlink_log_critical(mavlink_fd, "[cmd] command denied: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_FAILED:
+ mavlink_log_critical(mavlink_fd, "[cmd] command failed: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
+ mavlink_log_critical(mavlink_fd, "[cmd] command temporarily rejected: %u", cmd.command);
+ tune_negative();
+ break;
+
+ case VEHICLE_CMD_RESULT_UNSUPPORTED:
+ mavlink_log_critical(mavlink_fd, "[cmd] command unsupported: %u", cmd.command);
+ tune_negative();
+ break;
+
+ default:
+ break;
+ }
+}
+
+void *commander_low_prio_loop(void *arg)
+{
+ /* Set thread name */
+ prctl(PR_SET_NAME, "commander_low_prio", getpid());
+
+ /* Subscribe to command topic */
+ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ struct vehicle_command_s cmd;
+ memset(&cmd, 0, sizeof(cmd));
+
+ /* wakeup source(s) */
+ struct pollfd fds[1];
+
+ /* use the gyro to pace output - XXX BROKEN if we are using the L3GD20 */
+ fds[0].fd = cmd_sub;
+ fds[0].events = POLLIN;
+
+ while (!thread_should_exit) {
+
+ /* wait for up to 100ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 1000);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ /* if we reach here, we have a valid command */
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+
+ /* 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)
+ continue;
+
+ /* only handle low-priority commands here */
+ switch (cmd.command) {
+
+ case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
+ if (is_safe(&status, &safety, &armed)) {
+
+ if (((int)(cmd.param1)) == 1) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ usleep(1000000);
+ /* reboot */
+ systemreset(false);
+
+ } else if (((int)(cmd.param1)) == 3) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ usleep(1000000);
+ /* reboot to bootloader */
+ systemreset(true);
+
+ } else {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ }
+
+ } else {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ }
+
+ break;
+
+ case VEHICLE_CMD_PREFLIGHT_CALIBRATION: {
+
+ 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, ARMING_STATE_INIT, &armed)) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+ break;
+ }
+
+ if ((int)(cmd.param1) == 1) {
+ /* gyro calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_gyro_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param2) == 1) {
+ /* magnetometer calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_mag_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param3) == 1) {
+ /* zero-altitude pressure calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+
+ } else if ((int)(cmd.param4) == 1) {
+ /* RC calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
+
+ } else if ((int)(cmd.param5) == 1) {
+ /* accelerometer calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_accel_calibration(mavlink_fd);
+
+ } else if ((int)(cmd.param6) == 1) {
+ /* airspeed calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_airspeed_calibration(mavlink_fd);
+ }
+
+ if (calib_ret == OK)
+ tune_positive();
+ else
+ tune_negative();
+
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
+
+ break;
+ }
+
+ case VEHICLE_CMD_PREFLIGHT_STORAGE: {
+
+ if (((int)(cmd.param1)) == 0) {
+ if (0 == param_load_default()) {
+ mavlink_log_info(mavlink_fd, "[cmd] parameters loaded");
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "[cmd] parameters load ERROR");
+ answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
+ }
+
+ } else if (((int)(cmd.param1)) == 1) {
+ if (0 == param_save_default()) {
+ mavlink_log_info(mavlink_fd, "[cmd] parameters saved");
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "[cmd] parameters save error");
+ answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
+ }
+ }
+
+ break;
+ }
+
+ default:
+ answer_command(cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
+ break;
+ }
+
+ /* send any requested ACKs */
+ if (cmd.confirmation > 0 && cmd.command != VEHICLE_CMD_DO_SET_MODE
+ && cmd.command != VEHICLE_CMD_COMPONENT_ARM_DISARM) {
+ /* send acknowledge command */
+ // XXX TODO
+ }
+
+ }
+
+ return 0;
+}
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
new file mode 100644
index 000000000..5df5d8d0c
--- /dev/null
+++ b/src/modules/commander/commander_helper.cpp
@@ -0,0 +1,259 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file commander_helper.cpp
+ * Commander helper functions implementations
+ */
+
+#include <stdio.h>
+#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <fcntl.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 <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_tone_alarm.h>
+#include <drivers/drv_led.h>
+#include <drivers/drv_rgbled.h>
+
+
+#include "commander_helper.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+bool is_multirotor(const struct vehicle_status_s *current_status)
+{
+ return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_TRICOPTER));
+}
+
+bool is_rotary_wing(const struct vehicle_status_s *current_status)
+{
+ return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
+ || (current_status->system_type == VEHICLE_TYPE_COAXIAL);
+}
+
+static int buzzer;
+
+int buzzer_init()
+{
+ buzzer = open("/dev/tone_alarm", O_WRONLY);
+
+ if (buzzer < 0) {
+ warnx("Buzzer: open fail\n");
+ return ERROR;
+ }
+
+ return OK;
+}
+
+void buzzer_deinit()
+{
+ close(buzzer);
+}
+
+void tune_error()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 2);
+}
+
+void tune_positive()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 3);
+}
+
+void tune_neutral()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 4);
+}
+
+void tune_negative()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 5);
+}
+
+int tune_arm()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 12);
+}
+
+int tune_low_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 13);
+}
+
+int tune_critical_bat()
+{
+ return ioctl(buzzer, TONE_SET_ALARM, 14);
+}
+
+
+
+void tune_stop()
+{
+ ioctl(buzzer, TONE_SET_ALARM, 0);
+}
+
+static int leds;
+static int rgbleds;
+
+int led_init()
+{
+ /* first open normal LEDs */
+ leds = open(LED_DEVICE_PATH, 0);
+
+ if (leds < 0) {
+ warnx("LED: open fail\n");
+ 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;
+ }
+#endif
+
+ if (ioctl(leds, LED_ON, LED_AMBER)) {
+ warnx("Amber LED: ioctl fail\n");
+ return ERROR;
+ }
+
+ /* 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
+ }
+
+ return 0;
+}
+
+void led_deinit()
+{
+ close(leds);
+
+ if (rgbleds != -1) {
+ close(rgbleds);
+ }
+}
+
+int led_toggle(int led)
+{
+ return ioctl(leds, LED_TOGGLE, led);
+}
+
+int led_on(int led)
+{
+ return ioctl(leds, LED_ON, led);
+}
+
+int led_off(int led)
+{
+ return ioctl(leds, LED_OFF, led);
+}
+
+void rgbled_set_color(rgbled_color_t color) {
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+}
+
+void rgbled_set_mode(rgbled_mode_t mode) {
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+}
+
+void rgbled_set_pattern(rgbled_pattern_t *pattern) {
+
+ if (rgbleds != -1)
+ ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+}
+
+float battery_remaining_estimate_voltage(float voltage)
+{
+ float ret = 0;
+ static param_t bat_volt_empty;
+ static param_t bat_volt_full;
+ static param_t bat_n_cells;
+ static bool initialized = false;
+ static unsigned int counter = 0;
+ static float ncells = 3;
+ // XXX change cells to int (and param to INT32)
+
+ if (!initialized) {
+ bat_volt_empty = param_find("BAT_V_EMPTY");
+ bat_volt_full = param_find("BAT_V_FULL");
+ bat_n_cells = param_find("BAT_N_CELLS");
+ initialized = true;
+ }
+
+ static float chemistry_voltage_empty = 3.2f;
+ static float chemistry_voltage_full = 4.05f;
+
+ if (counter % 100 == 0) {
+ param_get(bat_volt_empty, &chemistry_voltage_empty);
+ param_get(bat_volt_full, &chemistry_voltage_full);
+ param_get(bat_n_cells, &ncells);
+ }
+
+ counter++;
+
+ ret = (voltage - ncells * chemistry_voltage_empty) / (ncells * (chemistry_voltage_full - chemistry_voltage_empty));
+
+ /* limit to sane values */
+ ret = (ret < 0.0f) ? 0.0f : ret;
+ ret = (ret > 1.0f) ? 1.0f : ret;
+ return ret;
+}
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
new file mode 100644
index 000000000..027d0535f
--- /dev/null
+++ b/src/modules/commander/commander_helper.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file commander_helper.h
+ * Commander helper functions definitions
+ */
+
+#ifndef COMMANDER_HELPER_H_
+#define COMMANDER_HELPER_H_
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <drivers/drv_rgbled.h>
+
+
+bool is_multirotor(const struct vehicle_status_s *current_status);
+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);
+
+int led_init(void);
+void led_deinit(void);
+int led_toggle(int led);
+int led_on(int led);
+int led_off(int led);
+
+void rgbled_set_color(rgbled_color_t color);
+
+void rgbled_set_mode(rgbled_mode_t mode);
+
+void rgbled_set_pattern(rgbled_pattern_t *pattern);
+
+/**
+ * Provides a coarse estimate of remaining battery power.
+ *
+ * The estimate is very basic and based on decharging voltage curves.
+ *
+ * @return the estimated remaining capacity in 0..1
+ */
+float battery_remaining_estimate_voltage(float voltage);
+
+#endif /* COMMANDER_HELPER_H_ */
diff --git a/src/modules/commander/commander.h b/src/modules/commander/commander_params.c
index 04b4e72ab..0a1703b2e 100644
--- a/src/modules/commander/commander.h
+++ b/src/modules/commander/commander_params.c
@@ -1,10 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 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>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,23 +33,22 @@
****************************************************************************/
/**
- * @file commander.h
- * Main system state machine definition.
+ * @file commander_params.c
+ *
+ * Parameters defined by the sensors task.
*
- * @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 <joes@student.ethz.ch>
- *
*/
-#ifndef COMMANDER_H_
-#define COMMANDER_H_
-
-#define LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 1000.0f
-#define CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS 100.0f
-
-void tune_confirm(void);
-void tune_error(void);
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
-#endif /* COMMANDER_H_ */
+PARAM_DEFINE_INT32(SYS_FAILSAFE_LL, 0); /**< Go into low-level failsafe after 0 ms */
+PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
+PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
+PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
+PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.2f);
+PARAM_DEFINE_FLOAT(BAT_V_FULL, 4.05f);
+PARAM_DEFINE_FLOAT(BAT_N_CELLS, 3);
diff --git a/src/modules/commander/commander_tests/commander_tests.cpp b/src/modules/commander/commander_tests/commander_tests.cpp
new file mode 100644
index 000000000..6e72cf0d9
--- /dev/null
+++ b/src/modules/commander/commander_tests/commander_tests.cpp
@@ -0,0 +1,55 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file commander_tests.cpp
+ * Commander unit tests. Run the tests as follows:
+ * nsh> commander_tests
+ *
+ */
+
+#include <systemlib/err.h>
+
+#include "state_machine_helper_test.h"
+
+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();
+
+ return 0;
+}
diff --git a/src/modules/commander/commander_tests/module.mk b/src/modules/commander/commander_tests/module.mk
new file mode 100644
index 000000000..4d10275d1
--- /dev/null
+++ b/src/modules/commander/commander_tests/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# 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
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# System state machine tests.
+#
+
+MODULE_COMMAND = commander_tests
+SRCS = commander_tests.cpp \
+ state_machine_helper_test.cpp \
+ ../state_machine_helper.cpp
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
new file mode 100644
index 000000000..40bedd9f3
--- /dev/null
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -0,0 +1,247 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file state_machine_helper_test.cpp
+ * System state machine unit test.
+ *
+ */
+
+#include "state_machine_helper_test.h"
+
+#include "../state_machine_helper.h"
+#include <unit_test/unit_test.h>
+
+class StateMachineHelperTest : public UnitTest
+{
+public:
+ StateMachineHelperTest();
+ virtual ~StateMachineHelperTest();
+
+ virtual const char* run_tests();
+
+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();
+};
+
+StateMachineHelperTest::StateMachineHelperTest() {
+}
+
+StateMachineHelperTest::~StateMachineHelperTest() {
+}
+
+const char*
+StateMachineHelperTest::arming_state_transition_test()
+{
+ 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 actuator_armed_s armed;
+
+ // TODO(sjwilks): ARM then DISARM.
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::main_state_transition_test()
+{
+ struct vehicle_status_s current_state;
+ main_state_t new_main_state;
+
+ // 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;
+}
+
+const char*
+StateMachineHelperTest::is_safe_test()
+{
+ struct vehicle_status_s current_state;
+ struct safety_s safety;
+ struct actuator_armed_s armed;
+
+ armed.armed = false;
+ armed.lockdown = false;
+ safety.safety_switch_available = true;
+ safety.safety_off = false;
+ mu_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));
+
+ 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));
+
+ 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));
+
+ 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));
+
+ return 0;
+}
+
+const char*
+StateMachineHelperTest::run_tests()
+{
+ 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;
+}
+
+void
+state_machine_helper_test()
+{
+ StateMachineHelperTest* test = new StateMachineHelperTest();
+ test->UnitTest::print_results(test->run_tests());
+}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.h b/src/modules/commander/commander_tests/state_machine_helper_test.h
new file mode 100644
index 000000000..10a68e602
--- /dev/null
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.h
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file state_machine_helper_test.h
+ */
+
+#ifndef STATE_MACHINE_HELPER_TEST_H_
+#define STATE_MACHINE_HELPER_TEST_
+
+void state_machine_helper_test();
+
+#endif /* STATE_MACHINE_HELPER_TEST_H_ */
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
new file mode 100644
index 000000000..33566d4e5
--- /dev/null
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -0,0 +1,289 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gyro_calibration.cpp
+ * Gyroscope calibration routine
+ */
+
+#include "gyro_calibration.h"
+#include "commander_helper.h"
+
+#include <stdio.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <math.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_gyro.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_gyro_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "Gyro calibration starting, do not move unit.");
+
+ const int calibration_count = 5000;
+
+ int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
+ struct sensor_combined_s raw;
+
+ int calibration_counter = 0;
+ float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
+
+ /* set offsets to zero */
+ int fd = open(GYRO_DEVICE_PATH, 0);
+ struct gyro_scale gscale_null = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
+ warn("WARNING: failed to set scale / offsets for gyro");
+
+ close(fd);
+
+ unsigned poll_errcount = 0;
+
+ while (calibration_counter < calibration_count) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_combined;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+ gyro_offset[0] += raw.gyro_rad_s[0];
+ gyro_offset[1] += raw.gyro_rad_s[1];
+ gyro_offset[2] += raw.gyro_rad_s[2];
+ calibration_counter++;
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_info(mavlink_fd, "ERROR: Failed reading gyro sensor");
+ return ERROR;
+ }
+ }
+
+ gyro_offset[0] = gyro_offset[0] / calibration_count;
+ gyro_offset[1] = gyro_offset[1] / calibration_count;
+ gyro_offset[2] = gyro_offset[2] / calibration_count;
+
+
+ if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
+
+ if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
+ || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
+ || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
+ mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
+ }
+
+ /* set offsets to actual value */
+ fd = open(GYRO_DEVICE_PATH, 0);
+ struct gyro_scale gscale = {
+ gyro_offset[0],
+ 1.0f,
+ gyro_offset[1],
+ 1.0f,
+ gyro_offset[2],
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ warn("WARNING: failed to set scale / offsets for gyro");
+
+ close(fd);
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warnx("WARNING: auto-save of params to storage failed");
+ mavlink_log_critical(mavlink_fd, "gyro store failed");
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, "gyro calibration done");
+
+ tune_neutral();
+ /* third beep by cal end routine */
+
+ } else {
+ mavlink_log_info(mavlink_fd, "offset cal FAILED (NaN)");
+ return ERROR;
+ }
+
+
+ /*** --- SCALING --- ***/
+
+ mavlink_log_info(mavlink_fd, "offset calibration finished. Rotate for scale 30x");
+ mavlink_log_info(mavlink_fd, "or do not rotate and wait for 5 seconds to skip.");
+ warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
+
+ unsigned rotations_count = 30;
+ float gyro_integral = 0.0f;
+ float baseline_integral = 0.0f;
+
+ // XXX change to mag topic
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+
+ 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;
+
+
+ uint64_t last_time = hrt_absolute_time();
+ uint64_t start_time = hrt_absolute_time();
+
+ while ((int)fabsf(baseline_integral / (2.0f * M_PI_F)) < rotations_count) {
+
+ /* abort this loop if not rotated more than 180 degrees within 5 seconds */
+ if ((fabsf(baseline_integral / (2.0f * M_PI_F)) < 0.6f)
+ && (hrt_absolute_time() - start_time > 5 * 1e6)) {
+ mavlink_log_info(mavlink_fd, "gyro scale calibration skipped");
+ mavlink_log_info(mavlink_fd, "gyro calibration done");
+ return OK;
+ }
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_combined;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+
+ float dt_ms = (hrt_absolute_time() - last_time) / 1e3f;
+ last_time = hrt_absolute_time();
+
+ orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
+
+ // XXX this is just a proof of concept and needs world / body
+ // transformation and more
+
+ //math::Vector2f magNav(raw.magnetometer_ga);
+
+ // calculate error between estimate and measurement
+ // apply declination correction for true heading as well.
+ //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;
+
+ 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;
+
+ baseline_integral += diff;
+ mag_last = mag;
+ // Jump through some timing scale hoops to avoid
+ // operating near the 1e6/1e8 max sane resolution of float.
+ gyro_integral += (raw.gyro_rad_s[2] * dt_ms) / 1e3f;
+
+// warnx("dbg: b: %6.4f, g: %6.4f", (double)baseline_integral, (double)gyro_integral);
+
+ // } else if (poll_ret == 0) {
+ // /* any poll failure for 1s is a reason to abort */
+ // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ // return;
+ }
+ }
+
+ float gyro_scale = baseline_integral / gyro_integral;
+ float gyro_scales[] = { gyro_scale, gyro_scale, gyro_scale };
+ warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale);
+ mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale);
+
+
+ if (isfinite(gyro_scales[0]) && isfinite(gyro_scales[1]) && isfinite(gyro_scales[2])) {
+
+ if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scales[0]))
+ || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scales[1]))
+ || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scales[2]))) {
+ mavlink_log_critical(mavlink_fd, "Setting gyro scale failed!");
+ }
+
+ /* set offsets to actual value */
+ fd = open(GYRO_DEVICE_PATH, 0);
+ struct gyro_scale gscale = {
+ gyro_offset[0],
+ gyro_scales[0],
+ gyro_offset[1],
+ gyro_scales[1],
+ gyro_offset[2],
+ gyro_scales[2],
+ };
+
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ warn("WARNING: failed to set scale / offsets for gyro");
+
+ close(fd);
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ }
+
+ // char buf[50];
+ // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
+ // mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "gyro calibration done");
+
+ /* third beep by cal end routine */
+ return OK;
+ } else {
+ mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
+ return ERROR;
+ }
+}
diff --git a/src/modules/commander/gyro_calibration.h b/src/modules/commander/gyro_calibration.h
new file mode 100644
index 000000000..59c32a15e
--- /dev/null
+++ b/src/modules/commander/gyro_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gyro_calibration.h
+ * Gyroscope calibration routine
+ */
+
+#ifndef GYRO_CALIBRATION_H_
+#define GYRO_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_gyro_calibration(int mavlink_fd);
+
+#endif /* GYRO_CALIBRATION_H_ */
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
new file mode 100644
index 000000000..e38616027
--- /dev/null
+++ b/src/modules/commander/mag_calibration.cpp
@@ -0,0 +1,298 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mag_calibration.cpp
+ * Magnetometer calibration routine
+ */
+
+#include "mag_calibration.h"
+#include "commander_helper.h"
+#include "calibration_routines.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <poll.h>
+#include <math.h>
+#include <fcntl.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/sensor_combined.h>
+#include <drivers/drv_mag.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_mag_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "please put the system in a rest position and wait.");
+
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ struct mag_report mag;
+
+ /* 45 seconds */
+ uint64_t calibration_interval = 45 * 1000 * 1000;
+
+ /* maximum 2000 values */
+ const unsigned int calibration_maxcount = 500;
+ unsigned int calibration_counter = 0;
+
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
+
+ int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ /* erase old calibration */
+ struct mag_scale mscale_null = {
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ 0.0f,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
+ warn("WARNING: failed to set scale / offsets for mag");
+ mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
+ }
+
+ /* calibrate range */
+ if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
+ warnx("failed to calibrate scale");
+ }
+
+ close(fd);
+
+ mavlink_log_info(mavlink_fd, "mag cal progress <20> percent");
+
+ /* calibrate offsets */
+
+ // uint64_t calibration_start = hrt_absolute_time();
+
+ uint64_t axis_deadline = hrt_absolute_time();
+ uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+
+ const char axislabels[3] = { 'X', 'Y', 'Z'};
+ int axis_index = -1;
+
+ float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
+ float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
+ float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
+
+ if (x == NULL || y == NULL || z == NULL) {
+ warnx("mag cal failed: out of memory");
+ mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
+ warnx("x:%p y:%p z:%p\n", x, y, z);
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, "scale calibration completed, dynamic calibration starting..");
+
+ unsigned poll_errcount = 0;
+
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_mag;
+ fds[0].events = POLLIN;
+
+ /* user guidance */
+ if (hrt_absolute_time() >= axis_deadline &&
+ axis_index < 3) {
+
+ axis_index++;
+
+ mavlink_log_info(mavlink_fd, "please rotate in a figure 8 or around %c axis.", axislabels[axis_index]);
+ mavlink_log_info(mavlink_fd, "mag cal progress <%u> percent", 20 + (calibration_maxcount * 50) / calibration_counter);
+ tune_neutral();
+
+ axis_deadline += calibration_interval / 3;
+ }
+
+ if (!(axis_index < 3)) {
+ break;
+ }
+
+ // int axis_left = (int64_t)axis_deadline - (int64_t)hrt_absolute_time();
+
+ // if ((axis_left / 1000) == 0 && axis_left > 0) {
+ // char buf[50];
+ // sprintf(buf, "[cmd] %d seconds left for axis %c", axis_left, axislabels[axis_index]);
+ // mavlink_log_info(mavlink_fd, buf);
+ // }
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
+
+ /* get min/max values */
+
+ // if (mag.x < mag_min[0]) {
+ // mag_min[0] = mag.x;
+ // }
+ // else if (mag.x > mag_max[0]) {
+ // mag_max[0] = mag.x;
+ // }
+
+ // if (raw.magnetometer_ga[1] < mag_min[1]) {
+ // mag_min[1] = raw.magnetometer_ga[1];
+ // }
+ // else if (raw.magnetometer_ga[1] > mag_max[1]) {
+ // mag_max[1] = raw.magnetometer_ga[1];
+ // }
+
+ // if (raw.magnetometer_ga[2] < mag_min[2]) {
+ // mag_min[2] = raw.magnetometer_ga[2];
+ // }
+ // else if (raw.magnetometer_ga[2] > mag_max[2]) {
+ // mag_max[2] = raw.magnetometer_ga[2];
+ // }
+
+ calibration_counter++;
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_info(mavlink_fd, "ERROR: Failed reading mag sensor");
+ return ERROR;
+ }
+
+
+ }
+
+ float sphere_x;
+ float sphere_y;
+ float sphere_z;
+ float sphere_radius;
+
+ sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
+
+ free(x);
+ free(y);
+ free(z);
+
+ if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
+
+ fd = open(MAG_DEVICE_PATH, 0);
+
+ struct mag_scale mscale;
+
+ if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
+ warn("WARNING: failed to get scale / offsets for mag");
+
+ mscale.x_offset = sphere_x;
+ mscale.y_offset = sphere_y;
+ mscale.z_offset = sphere_z;
+
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
+ warn("WARNING: failed to set scale / offsets for mag");
+
+ close(fd);
+
+ /* announce and set new offset */
+
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
+ warnx("Setting X mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
+ warnx("Setting Y mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
+ warnx("Setting Z mag offset failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
+ warnx("Setting X mag scale failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
+ warnx("Setting Y mag scale failed!\n");
+ }
+
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
+ warnx("Setting Z mag scale failed!\n");
+ }
+
+ mavlink_log_info(mavlink_fd, "mag cal progress <90> percent");
+
+ /* auto-save to EEPROM */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ warn("WARNING: auto-save of params to storage failed");
+ mavlink_log_info(mavlink_fd, "FAILED storing calibration");
+ return ERROR;
+ }
+
+ warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
+ (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
+ (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
+
+ char buf[52];
+ sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
+ (double)mscale.y_offset, (double)mscale.z_offset);
+ mavlink_log_info(mavlink_fd, buf);
+
+ sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
+ (double)mscale.y_scale, (double)mscale.z_scale);
+ mavlink_log_info(mavlink_fd, buf);
+
+ mavlink_log_info(mavlink_fd, "magnetometer calibration completed");
+ mavlink_log_info(mavlink_fd, "mag cal progress <100> percent");
+
+ return OK;
+ /* third beep by cal end routine */
+
+ } else {
+ mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
+ return ERROR;
+ }
+}
diff --git a/src/modules/commander/mag_calibration.h b/src/modules/commander/mag_calibration.h
new file mode 100644
index 000000000..a101cd7b1
--- /dev/null
+++ b/src/modules/commander/mag_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mag_calibration.h
+ * Magnetometer calibration routine
+ */
+
+#ifndef MAG_CALIBRATION_H_
+#define MAG_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_mag_calibration(int mavlink_fd);
+
+#endif /* MAG_CALIBRATION_H_ */
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index fe44e955a..91d75121e 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -36,8 +36,15 @@
#
MODULE_COMMAND = commander
-SRCS = commander.c \
- state_machine_helper.c \
- calibration_routines.c \
- accelerometer_calibration.c
+SRCS = commander.cpp \
+ commander_params.c \
+ state_machine_helper.cpp \
+ commander_helper.cpp \
+ calibration_routines.cpp \
+ accelerometer_calibration.cpp \
+ gyro_calibration.cpp \
+ mag_calibration.cpp \
+ baro_calibration.cpp \
+ rc_calibration.cpp \
+ airspeed_calibration.cpp
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
new file mode 100644
index 000000000..b60a7e0b9
--- /dev/null
+++ b/src/modules/commander/px4_custom_mode.h
@@ -0,0 +1,37 @@
+/*
+ * px4_custom_mode.h
+ *
+ * Created on: 09.08.2013
+ * Author: ton
+ */
+
+#ifndef PX4_CUSTOM_MODE_H_
+#define PX4_CUSTOM_MODE_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_AUTO,
+};
+
+enum PX4_CUSTOM_SUB_MODE_AUTO {
+ PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
+ PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
+ PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
+ PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
+ PX4_CUSTOM_SUB_MODE_AUTO_RTL,
+ PX4_CUSTOM_SUB_MODE_AUTO_LAND,
+};
+
+union px4_custom_mode {
+ struct {
+ uint16_t reserved;
+ uint8_t main_mode;
+ uint8_t sub_mode;
+ };
+ uint32_t data;
+ float data_float;
+};
+
+#endif /* PX4_CUSTOM_MODE_H_ */
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
new file mode 100644
index 000000000..fe87a3323
--- /dev/null
+++ b/src/modules/commander/rc_calibration.cpp
@@ -0,0 +1,88 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_calibration.cpp
+ * Remote Control calibration routine
+ */
+
+#include "rc_calibration.h"
+#include "commander_helper.h"
+
+#include <poll.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int do_rc_calibration(int mavlink_fd)
+{
+ mavlink_log_info(mavlink_fd, "trim calibration starting");
+
+ /* XXX fix this */
+ // if (current_status.rc_signal) {
+ // mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal.");
+ // return;
+ // }
+
+ int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
+ struct manual_control_setpoint_s sp;
+ orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
+
+ /* set parameters */
+ float p = sp.roll;
+ param_set(param_find("TRIM_ROLL"), &p);
+ p = sp.pitch;
+ param_set(param_find("TRIM_PITCH"), &p);
+ p = sp.yaw;
+ param_set(param_find("TRIM_YAW"), &p);
+
+ /* store to permanent storage */
+ /* auto-save */
+ int save_ret = param_save_default();
+
+ if (save_ret != 0) {
+ mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, "trim calibration done");
+ return OK;
+}
diff --git a/src/modules/commander/rc_calibration.h b/src/modules/commander/rc_calibration.h
new file mode 100644
index 000000000..9aa6faafa
--- /dev/null
+++ b/src/modules/commander/rc_calibration.h
@@ -0,0 +1,46 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_calibration.h
+ * Remote Control calibration routine
+ */
+
+#ifndef RC_CALIBRATION_H_
+#define RC_CALIBRATION_H_
+
+#include <stdint.h>
+
+int do_rc_calibration(int mavlink_fd);
+
+#endif /* RC_CALIBRATION_H_ */
diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c
deleted file mode 100644
index ab728c7bb..000000000
--- a/src/modules/commander/state_machine_helper.c
+++ /dev/null
@@ -1,757 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file state_machine_helper.c
- * State machine helper functions implementations
- */
-
-#include <stdio.h>
-#include <unistd.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/actuator_controls.h>
-#include <systemlib/systemlib.h>
-#include <drivers/drv_hrt.h>
-#include <mavlink/mavlink_log.h>
-
-#include "state_machine_helper.h"
-
-static const char *system_state_txt[] = {
- "SYSTEM_STATE_PREFLIGHT",
- "SYSTEM_STATE_STANDBY",
- "SYSTEM_STATE_GROUND_READY",
- "SYSTEM_STATE_MANUAL",
- "SYSTEM_STATE_STABILIZED",
- "SYSTEM_STATE_AUTO",
- "SYSTEM_STATE_MISSION_ABORT",
- "SYSTEM_STATE_EMCY_LANDING",
- "SYSTEM_STATE_EMCY_CUTOFF",
- "SYSTEM_STATE_GROUND_ERROR",
- "SYSTEM_STATE_REBOOT",
-
-};
-
-/**
- * Transition from one state to another
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state)
-{
- int invalid_state = false;
- int ret = ERROR;
-
- commander_state_machine_t old_state = current_status->state_machine;
-
- switch (new_state) {
- case SYSTEM_STATE_MISSION_ABORT: {
- /* Indoor or outdoor */
- // if (flight_environment_parameter == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
- ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_LANDING);
-
- // } else {
- // ret = do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_EMCY_CUTOFF);
- // }
- }
- break;
-
- case SYSTEM_STATE_EMCY_LANDING:
- /* Tell the controller to land */
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- warnx("EMERGENCY LANDING!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY LANDING!");
- break;
-
- case SYSTEM_STATE_EMCY_CUTOFF:
- /* Tell the controller to cutoff the motors (thrust = 0) */
-
- /* set system flags according to state */
- current_status->flag_system_armed = false;
-
- warnx("EMERGENCY MOTOR CUTOFF!\n");
- mavlink_log_critical(mavlink_fd, "EMERGENCY MOTOR CUTOFF!");
- break;
-
- case SYSTEM_STATE_GROUND_ERROR:
-
- /* set system flags according to state */
-
- /* prevent actuators from arming */
- current_status->flag_system_armed = false;
-
- warnx("GROUND ERROR, locking down propulsion system\n");
- mavlink_log_critical(mavlink_fd, "GROUND ERROR, locking down system");
- break;
-
- case SYSTEM_STATE_PREFLIGHT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "Switched to PREFLIGHT state");
-
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to switch to PREFLIGHT state");
- }
-
- break;
-
- case SYSTEM_STATE_REBOOT:
- if (current_status->state_machine == SYSTEM_STATE_STANDBY
- || current_status->state_machine == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- invalid_state = false;
- /* set system flags according to state */
- current_status->flag_system_armed = false;
- mavlink_log_critical(mavlink_fd, "REBOOTING SYSTEM");
- usleep(500000);
- up_systemreset();
- /* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */
-
- } else {
- invalid_state = true;
- mavlink_log_critical(mavlink_fd, "REFUSED to REBOOT");
- }
-
- break;
-
- case SYSTEM_STATE_STANDBY:
- /* set system flags according to state */
-
- /* standby enforces disarmed */
- current_status->flag_system_armed = false;
-
- mavlink_log_critical(mavlink_fd, "Switched to STANDBY state");
- break;
-
- case SYSTEM_STATE_GROUND_READY:
-
- /* set system flags according to state */
-
- /* ground ready has motors / actuators armed */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to GROUND READY state");
- break;
-
- case SYSTEM_STATE_AUTO:
-
- /* set system flags according to state */
-
- /* auto is airborne and in auto mode, motors armed */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / AUTO mode");
- break;
-
- case SYSTEM_STATE_STABILIZED:
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / STABILIZED mode");
- break;
-
- case SYSTEM_STATE_MANUAL:
-
- /* set system flags according to state */
- current_status->flag_system_armed = true;
-
- mavlink_log_critical(mavlink_fd, "Switched to FLYING / MANUAL mode");
- break;
-
- default:
- invalid_state = true;
- break;
- }
-
- if (invalid_state == false || old_state != new_state) {
- current_status->state_machine = new_state;
- state_machine_publish(status_pub, current_status, mavlink_fd);
- publish_armed_status(current_status);
- ret = OK;
- }
-
- if (invalid_state) {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid state transition");
- ret = ERROR;
- }
-
- return ret;
-}
-
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* publish the new state */
- current_status->counter++;
- current_status->timestamp = hrt_absolute_time();
-
- /* assemble state vector based on flag values */
- if (current_status->flag_control_rates_enabled) {
- current_status->onboard_control_sensors_present |= 0x400;
-
- } else {
- current_status->onboard_control_sensors_present &= ~0x400;
- }
-
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_present |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
-
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_rates_enabled) ? 0x400 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x800 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_attitude_enabled) ? 0x1000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x2000 : 0;
- current_status->onboard_control_sensors_enabled |= (current_status->flag_control_velocity_enabled || current_status->flag_control_position_enabled) ? 0x4000 : 0;
-
- orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
- printf("[cmd] new state: %s\n", system_state_txt[current_status->state_machine]);
-}
-
-void publish_armed_status(const struct vehicle_status_s *current_status)
-{
- struct actuator_armed_s armed;
- armed.armed = current_status->flag_system_armed;
-
- /* XXX allow arming by external components on multicopters only if not yet armed by RC */
- /* XXX allow arming only if core sensors are ok */
- armed.ready_to_arm = true;
-
- /* lock down actuators if required, only in HIL */
- armed.lockdown = (current_status->flag_hil_enabled) ? true : false;
- orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
- orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
-}
-
-
-/*
- * Private functions, update the state machine
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- warnx("EMERGENCY HANDLER\n");
- /* Depending on the current state go to one of the error states */
-
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT || current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_ERROR);
-
- } else if (current_status->state_machine == SYSTEM_STATE_AUTO || current_status->state_machine == SYSTEM_STATE_MANUAL) {
-
- // DO NOT abort mission
- //do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MISSION_ABORT);
-
- } else {
- warnx("Unknown system state: #%d\n", current_status->state_machine);
- }
-}
-
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd) //do not call state_machine_emergency_always_critical if we are in manual mode for these errors
-{
- if (current_status->state_machine != SYSTEM_STATE_MANUAL) { //if we are in manual: user can react to errors themself
- state_machine_emergency_always_critical(status_pub, current_status, mavlink_fd);
-
- } else {
- //global_data_send_mavlink_statustext_message_out("[cmd] ERROR: take action immediately! (did not switch to error state because the system is in manual mode)", MAV_SEVERITY_CRITICAL);
- }
-
-}
-
-
-
-// /*
-// * 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;
-// }
-
-// }
-
-
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_health |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //TODO state machine change (recovering)
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //TODO state machine change
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// //TODO state machine change
-// break;
-
-// default:
-// break;
-// }
-
-
-// }
-
-
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// bool previosly_healthy = (bool)(current_status->onboard_control_sensors_health & 1 << *subsystem_type);
-// current_status->onboard_control_sensors_health &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if we received unhealthy message more than *_HEALTH_COUNTER_LIMIT, switch to error state */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer unhealthy", MAV_SEVERITY_CRITICAL);
-
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency_always_critical(status_pub, current_status);
-
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// // //TODO: remove this block
-// // break;
-// // ///////////////////
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS unhealthy", MAV_SEVERITY_CRITICAL);
-
-// // printf("previosly_healthy = %u\n", previosly_healthy);
-// if (previosly_healthy) //only throw emergency if previously healthy
-// state_machine_emergency(status_pub, current_status);
-
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-/* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
-
-
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- /* Depending on the current state switch state */
- if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_AUTO) {
- state_machine_emergency(status_pub, current_status, mavlink_fd);
- }
-}
-
-void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_STANDBY) {
- printf("[cmd] arming\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
- }
-}
-
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
- printf("[cmd] going standby\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
-
- } else if (current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] MISSION ABORT!\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
- }
-}
-
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
-
- current_status->flag_control_manual_enabled = true;
-
- /* set behaviour based on airframe */
- if ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_OCTOROTOR)) {
-
- /* assuming a rotary wing, set to SAS */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
-
- } else {
-
- /* assuming a fixed wing, set to direct pass-through */
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_DIRECT;
- current_status->flag_control_attitude_enabled = false;
- current_status->flag_control_rates_enabled = false;
- }
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] manual mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- }
-}
-
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_STABILIZED || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- int old_mode = current_status->flight_mode;
- int old_manual_control_mode = current_status->manual_control_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_MANUAL;
- current_status->manual_control_mode = VEHICLE_MANUAL_CONTROL_MODE_SAS;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- current_status->flag_control_manual_enabled = true;
-
- if (old_mode != current_status->flight_mode ||
- old_manual_control_mode != current_status->manual_control_mode) {
- printf("[cmd] att stabilized mode\n");
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-
- }
-}
-
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. GUIDED MODE");
- tune_error();
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_AUTO) {
- printf("[cmd] position guided mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_STAB;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STABILIZED);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
-
- }
-}
-
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
-{
- if (!current_status->flag_vector_flight_mode_ok) {
- mavlink_log_critical(mavlink_fd, "NO POS LOCK, REJ. AUTO MODE");
- return;
- }
-
- if (current_status->state_machine == SYSTEM_STATE_GROUND_READY || current_status->state_machine == SYSTEM_STATE_MANUAL || current_status->state_machine == SYSTEM_STATE_STABILIZED) {
- printf("[cmd] auto mode\n");
- int old_mode = current_status->flight_mode;
- current_status->flight_mode = VEHICLE_FLIGHT_MODE_AUTO;
- current_status->flag_control_manual_enabled = false;
- current_status->flag_control_attitude_enabled = true;
- current_status->flag_control_rates_enabled = true;
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
-
- if (old_mode != current_status->flight_mode) state_machine_publish(status_pub, current_status, mavlink_fd);
- }
-}
-
-
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
-{
- uint8_t 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_system_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_system_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_system_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;
-}
-
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode) //TODO: add more checks to avoid state switching in critical situations
-{
- commander_state_machine_t current_system_state = current_status->state_machine;
-
- uint8_t ret = 1;
-
- switch (custom_mode) {
- case SYSTEM_STATE_GROUND_READY:
- break;
-
- case SYSTEM_STATE_STANDBY:
- break;
-
- case SYSTEM_STATE_REBOOT:
- printf("try to reboot\n");
-
- if (current_system_state == SYSTEM_STATE_STANDBY
- || current_system_state == SYSTEM_STATE_PREFLIGHT
- || current_status->flag_hil_enabled) {
- printf("system will reboot\n");
- mavlink_log_critical(mavlink_fd, "Rebooting..");
- usleep(200000);
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_REBOOT);
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_AUTO:
- printf("try to switch to auto/takeoff\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_MANUAL) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_AUTO);
- printf("state: auto\n");
- ret = 0;
- }
-
- break;
-
- case SYSTEM_STATE_MANUAL:
- printf("try to switch to manual\n");
-
- if (current_system_state == SYSTEM_STATE_GROUND_READY || current_system_state == SYSTEM_STATE_AUTO) {
- do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_MANUAL);
- printf("state: manual\n");
- ret = 0;
- }
-
- break;
-
- default:
- break;
- }
-
- return ret;
-}
-
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
new file mode 100644
index 000000000..674f3feda
--- /dev/null
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -0,0 +1,703 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file state_machine_helper.cpp
+ * State machine helper functions implementations
+ */
+
+#include <stdio.h>
+#include <unistd.h>
+#include <stdint.h>
+#include <stdbool.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 <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <mavlink/mavlink_log.h>
+
+#include "state_machine_helper.h"
+#include "commander_helper.h"
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+static bool arming_state_changed = true;
+static bool main_state_changed = true;
+static bool navigation_state_changed = true;
+
+transition_result_t
+arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety, arming_state_t new_arming_state, struct actuator_armed_s *armed)
+{
+ /*
+ * Perform an atomic state update
+ */
+ irqstate_t flags = irqsave();
+
+ transition_result_t ret = TRANSITION_DENIED;
+
+ /* only check transition if the new state is actually different from the current one */
+ if (new_arming_state == status->arming_state) {
+ ret = TRANSITION_NOT_CHANGED;
+
+ } else {
+
+ switch (new_arming_state) {
+ case ARMING_STATE_INIT:
+
+ /* allow going back from INIT for calibration */
+ if (status->arming_state == ARMING_STATE_STANDBY) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_STANDBY:
+
+ /* allow coming from INIT and disarming from ARMED */
+ if (status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_ARMED) {
+
+ /* sensors need to be initialized for STANDBY state */
+ if (status->condition_system_sensors_initialized) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = true;
+ }
+ }
+
+ break;
+
+ case ARMING_STATE_ARMED:
+
+ /* allow arming from STANDBY and IN-AIR-RESTORE */
+ if ((status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
+ && (!safety->safety_switch_available || safety->safety_off)) { /* only allow arming if safety is off */
+ ret = TRANSITION_CHANGED;
+ armed->armed = true;
+ armed->ready_to_arm = true;
+ }
+
+ break;
+
+ case ARMING_STATE_ARMED_ERROR:
+
+ /* an armed error happens when ARMED obviously */
+ if (status->arming_state == ARMING_STATE_ARMED) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = true;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_STANDBY_ERROR:
+
+ /* a disarmed error happens when in STANDBY or in INIT or after ARMED_ERROR */
+ if (status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_REBOOT:
+
+ /* an armed error happens when ARMED obviously */
+ if (status->arming_state == ARMING_STATE_INIT
+ || status->arming_state == ARMING_STATE_STANDBY
+ || status->arming_state == ARMING_STATE_STANDBY_ERROR) {
+ ret = TRANSITION_CHANGED;
+ armed->armed = false;
+ armed->ready_to_arm = false;
+ }
+
+ break;
+
+ case ARMING_STATE_IN_AIR_RESTORE:
+
+ /* XXX implement */
+ break;
+
+ default:
+ break;
+ }
+
+ if (ret == TRANSITION_CHANGED) {
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
+ /* end of atomic state update */
+ irqrestore(flags);
+
+ if (ret == TRANSITION_DENIED)
+ warnx("arming transition rejected");
+
+ return ret;
+}
+
+bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safety, const struct actuator_armed_s *armed)
+{
+ // System is safe if:
+ // 1) Not armed
+ // 2) Armed, but in software lockdown (HIL)
+ // 3) Safety switch is present AND engaged -> actuators locked
+ if (!armed->armed || (armed->armed && armed->lockdown) || (safety->safety_switch_available && !safety->safety_off)) {
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+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)
+{
+ 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:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_SEATBELT:
+
+ /* need altitude estimate */
+ if (current_state->condition_local_altitude_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+
+ break;
+
+ case MAIN_STATE_EASY:
+
+ /* need local position estimate */
+ if (current_state->condition_local_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;
+}
+
+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:
+ 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;
+
+ case NAVIGATION_STATE_AUTO_TAKEOFF:
+
+ /* only transitions from AUTO_READY */
+ 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;
+
+ case NAVIGATION_STATE_AUTO_LOITER:
+ 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;
+
+ 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 NAVIGATION_STATE_AUTO_RTL:
+ 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;
+ }
+ }
+
+ 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)
+{
+ bool valid_transition = false;
+ int ret = ERROR;
+
+ warnx("Current state: %d, requested state: %d", current_status->hil_state, new_state);
+
+ if (current_status->hil_state == new_state) {
+ warnx("Hil state not changed");
+ valid_transition = true;
+
+ } else {
+
+ switch (new_state) {
+
+ case HIL_STATE_OFF:
+
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY) {
+
+ current_control_mode->flag_system_hil_enabled = false;
+ mavlink_log_critical(mavlink_fd, "Switched to OFF hil state");
+ valid_transition = true;
+ }
+
+ break;
+
+ case HIL_STATE_ON:
+
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY) {
+
+ current_control_mode->flag_system_hil_enabled = true;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
+ valid_transition = true;
+ }
+
+ break;
+
+ default:
+ warnx("Unknown hil state");
+ break;
+ }
+ }
+
+ if (valid_transition) {
+ current_status->hil_state = new_state;
+
+ current_status->counter++;
+ current_status->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+
+ current_control_mode->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, current_control_mode);
+
+ ret = OK;
+
+ } else {
+ mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
+ }
+
+ return ret;
+}
+
+
+
+// /*
+// * 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;
+//}
+
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 2f2ccc729..1641b6f60 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
*
@@ -46,164 +46,34 @@
#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>
-/**
- * Switch to new state with no checking.
- *
- * do_state_update: this is the functions that all other functions have to call in order to update the state.
- * the function does not question the state change, this must be done before
- * The function performs actions that are connected with the new state (buzzer, reboot, ...)
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- *
- * @return 0 (macro OK) or 1 on error (macro ERROR)
- */
-int do_state_update(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, commander_state_machine_t new_state);
+typedef enum {
+ TRANSITION_DENIED = -1,
+ TRANSITION_NOT_CHANGED = 0,
+ TRANSITION_CHANGED
-/* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR */
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+} transition_result_t;
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+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);
-// void update_state_machine_subsystem_healthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
-// void update_state_machine_subsystem_unhealthy(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type);
+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();
-/**
- * Handle state machine if got position fix
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_got_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
-/**
- * Handle state machine if position fix lost
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_no_position_fix(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+bool check_main_state_changed();
-/**
- * Handle state machine if user wants to arm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_arm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
+transition_result_t navigation_state_transition(struct vehicle_status_s *status, navigation_state_t new_navigation_state, struct vehicle_control_mode_s *control_mode);
-/**
- * Handle state machine if user wants to disarm
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_disarm(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is manual
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_manual(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is stabilized
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_stabilized(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is guided
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_guided(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Handle state machine if mode switch is auto
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void update_state_machine_mode_auto(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish current state information
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_publish(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-
-/*
- * Functions that handle incoming requests to change the state machine or a parameter (probably from the mavlink app).
- * If the request is obeyed the functions return 0
- *
- */
-
-/**
- * Handles *incoming request* to switch to a specific state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode);
-
-/**
- * Handles *incoming request* to switch to a specific custom state, if state change is successful returns 0
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-uint8_t update_state_machine_custom_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t custom_mode);
-
-/**
- * Always switches to critical mode under any circumstances.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency_always_critical(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Switches to emergency if required.
- *
- * @param status_pub file descriptor for state update topic publication
- * @param current_status pointer to the current state machine to operate on
- * @param mavlink_fd file descriptor for MAVLink statustext messages
- */
-void state_machine_emergency(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd);
-
-/**
- * Publish the armed state depending on the current system state
- *
- * @param current_status the current system status
- */
-void publish_armed_status(const struct vehicle_status_s *current_status);
+bool check_navigation_state_changed();
+void set_navigation_state_changed();
+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);
#endif /* STATE_MACHINE_HELPER_H_ */