aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander/state_machine_helper.cpp')
-rw-r--r--src/modules/commander/state_machine_helper.cpp1018
1 files changed, 475 insertions, 543 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 7ae61d9ef..423ce2f23 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,6 +34,9 @@
/**
* @file state_machine_helper.cpp
* State machine helper functions implementations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <stdio.h>
@@ -44,15 +45,19 @@
#include <stdbool.h>
#include <dirent.h>
#include <fcntl.h>
+#include <string.h>
+#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/differential_pressure.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_airspeed.h>
#include <drivers/drv_device.h>
#include <mavlink/mavlink_log.h>
@@ -65,134 +70,159 @@
#endif
static const int ERROR = -1;
-static bool arming_state_changed = true;
-static bool main_state_changed = true;
-static bool navigation_state_changed = true;
+static int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
+
+// This array defines the arming state transitions. The rows are the new state, and the columns
+// are the current state. Using new state and current state you can index into the array which
+// will be true for a valid transition or false for a invalid transition. In some cases even
+// though the transition is marked as true additional checks must be made. See arming_state_transition
+// code for those checks.
+static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+};
+
+// You can index into the array with an arming_state_t in order to get it's textual representation
+static const char *state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
+};
transition_result_t
-arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety,
- const struct vehicle_control_mode_s *control_mode,
- arming_state_t new_arming_state, struct actuator_armed_s *armed)
+arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
- /*
- * Perform an atomic state update
- */
- irqstate_t flags = irqsave();
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
transition_result_t ret = TRANSITION_DENIED;
+ arming_state_t current_arming_state = status->arming_state;
+
/* only check transition if the new state is actually different from the current one */
- if (new_arming_state == status->arming_state) {
+ if (new_arming_state == current_arming_state) {
ret = TRANSITION_NOT_CHANGED;
} else {
+ /*
+ * Get sensing state if necessary
+ */
+ int prearm_ret = OK;
+
+ /* only perform the check if we have to */
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ prearm_ret = prearm_check(status, mavlink_fd);
+ }
+
+ /*
+ * Perform an atomic state update
+ */
+ irqstate_t flags = irqsave();
+
/* enforce lockdown in HIL */
- if (control_mode->flag_system_hil_enabled) {
+ if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
+
} else {
armed->lockdown = false;
}
- switch (new_arming_state) {
- case ARMING_STATE_INIT:
-
- /* 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
- || control_mode->flag_system_hil_enabled) {
-
- /* 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;
- }
- }
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
- break;
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
- case ARMING_STATE_ARMED:
+ // Do not perform pre-arm checks if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE &&
+ status->hil_state == HIL_STATE_OFF) {
- /* allow arming from STANDBY and IN-AIR-RESTORE */
- if ((status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
- && (!safety->safety_switch_available || safety->safety_off || control_mode->flag_system_hil_enabled)) { /* only allow arming if safety is off */
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = true;
- }
+ // Fail transition if pre-arm check fails
+ if (prearm_ret) {
+ valid_transition = false;
- break;
+ // Fail transition if we need safety switch press
+ } else if (safety->safety_switch_available && !safety->safety_off) {
- case ARMING_STATE_ARMED_ERROR:
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch!");
- /* an armed error happens when ARMED obviously */
- if (status->arming_state == ARMING_STATE_ARMED) {
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = false;
- }
+ valid_transition = false;
+ }
- break;
+ // Perform power checks only if circuit breaker is not
+ // engaged for these checks
+ if (!status->circuit_breaker_engaged_power_check) {
+ // Fail transition if power is not good
+ if (!status->condition_power_input_valid) {
- case ARMING_STATE_STANDBY_ERROR:
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Connect power module.");
+ valid_transition = false;
+ }
- /* a disarmed error happens when in STANDBY or in INIT or after ARMED_ERROR */
- if (status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED_ERROR) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
- }
+ // Fail transition if power levels on the avionics rail
+ // are measured but are insufficient
+ if (status->condition_power_input_valid && (status->avionics_power_rail_voltage > 0.0f) &&
+ (status->avionics_power_rail_voltage < 4.9f)) {
- break;
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
+ valid_transition = false;
+ }
+ }
- case ARMING_STATE_REBOOT:
+ }
- /* an armed error happens when ARMED obviously */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
}
+ }
- break;
-
- case ARMING_STATE_IN_AIR_RESTORE:
-
- /* XXX implement */
- break;
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
- default:
- break;
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
}
- if (ret == TRANSITION_CHANGED) {
+ // Finish up the state transition
+ if (valid_transition) {
+ armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
+ armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
+ ret = TRANSITION_CHANGED;
status->arming_state = new_arming_state;
- arming_state_changed = true;
}
+
+ /* end of atomic state update */
+ irqrestore(flags);
}
- /* end of atomic state update */
- irqrestore(flags);
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "INVAL: %s - %s";
- if (ret == TRANSITION_DENIED)
- warnx("arming transition rejected");
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
@@ -211,528 +241,430 @@ bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safet
}
}
-bool
-check_arming_state_changed()
-{
- if (arming_state_changed) {
- arming_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
transition_result_t
-main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state)
+main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state)
{
transition_result_t ret = TRANSITION_DENIED;
- /* only check transition if the new state is actually different from the current one */
- if (new_main_state == current_state->main_state) {
- ret = TRANSITION_NOT_CHANGED;
-
- } else {
-
- switch (new_main_state) {
- case MAIN_STATE_MANUAL:
+ /* transition may be denied even if the same state is requested because conditions may have changed */
+ switch (new_main_state) {
+ case MAIN_STATE_MANUAL:
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_ALTCTL:
+ /* need at minimum altitude estimate */
+ /* TODO: add this for fixedwing as well */
+ if (!status->is_rotary_wing ||
+ (status->condition_local_altitude_valid ||
+ status->condition_global_position_valid)) {
ret = TRANSITION_CHANGED;
- break;
-
- case MAIN_STATE_SEATBELT:
-
- /* need at minimum altitude estimate */
- if (current_state->condition_local_altitude_valid ||
- current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
-
- break;
-
- case MAIN_STATE_EASY:
-
- /* need at minimum local position estimate */
- if (current_state->condition_local_position_valid ||
- current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
-
- break;
+ }
+ break;
- case MAIN_STATE_AUTO:
+ case MAIN_STATE_POSCTL:
+ /* need at minimum local position estimate */
+ if (status->condition_local_position_valid ||
+ status->condition_global_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+ break;
- /* need global position estimate */
- if (current_state->condition_global_position_valid) {
- ret = TRANSITION_CHANGED;
- }
+ case MAIN_STATE_AUTO_MISSION:
+ case MAIN_STATE_AUTO_LOITER:
+ /* need global position estimate */
+ if (status->condition_global_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+ break;
- break;
+ case MAIN_STATE_AUTO_RTL:
+ /* need global position and home position */
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ ret = TRANSITION_CHANGED;
}
+ break;
- if (ret == TRANSITION_CHANGED) {
- current_state->main_state = new_main_state;
- main_state_changed = true;
+ case MAIN_STATE_MAX:
+ default:
+ break;
+ }
+ if (ret == TRANSITION_CHANGED) {
+ if (status->main_state != new_main_state) {
+ status->main_state = new_main_state;
+ } else {
+ ret = TRANSITION_NOT_CHANGED;
}
}
return ret;
}
-bool
-check_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 from one hil state to another
+ */
+transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
{
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) {
+ if (current_status->hil_state == new_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;
+ switch (new_state) {
+ case HIL_STATE_OFF:
+ /* we're in HIL and unexpected things can happen if we disable HIL now */
+ mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
+ ret = TRANSITION_DENIED;
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 HIL_STATE_ON:
+ if (current_status->arming_state == ARMING_STATE_INIT
+ || current_status->arming_state == ARMING_STATE_STANDBY
+ || current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- 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;
+ /* Disable publication of all attached sensors */
+ /* list directory */
+ DIR *d;
+ d = opendir("/dev");
- 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;
+ if (d) {
+ struct dirent *direntry;
+ char devname[24];
- 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;
+ while ((direntry = readdir(d)) != NULL) {
- case NAVIGATION_STATE_AUTO_TAKEOFF:
- 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;
+ /* skip serial ports */
+ if (!strncmp("tty", direntry->d_name, 3)) {
+ continue;
+ }
- 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;
+ /* skip mtd devices */
+ if (!strncmp("mtd", direntry->d_name, 3)) {
+ continue;
+ }
- 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;
+ /* skip ram devices */
+ if (!strncmp("ram", direntry->d_name, 3)) {
+ continue;
+ }
- 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;
+ /* skip MMC devices */
+ if (!strncmp("mmc", direntry->d_name, 3)) {
+ continue;
+ }
- 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;
- }
+ /* skip mavlink */
+ if (!strcmp("mavlink", direntry->d_name)) {
+ continue;
+ }
+
+ /* skip console */
+ if (!strcmp("console", direntry->d_name)) {
+ continue;
+ }
+
+ /* skip null */
+ if (!strcmp("null", direntry->d_name)) {
+ continue;
+ }
+
+ snprintf(devname, sizeof(devname), "/dev/%s", direntry->d_name);
+
+ int sensfd = ::open(devname, 0);
+
+ if (sensfd < 0) {
+ warn("failed opening device %s", devname);
+ continue;
+ }
+ int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 1);
+ close(sensfd);
+
+ printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR");
+ }
+ closedir(d);
+ ret = TRANSITION_CHANGED;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
+
+
+ } else {
+ /* failed opening dir */
+ mavlink_log_info(mavlink_fd, "FAILED LISTING DEVICE ROOT DIRECTORY");
+ ret = TRANSITION_DENIED;
+ }
+ } else {
+ mavlink_log_critical(mavlink_fd, "Not switching to HIL when armed");
+ ret = TRANSITION_DENIED;
+ }
break;
default:
+ warnx("Unknown HIL state");
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;
+ if (ret == TRANSITION_CHANGED) {
+ current_status->hil_state = new_state;
+ current_status->timestamp = hrt_absolute_time();
+ // XXX also set lockdown here
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
}
-}
-
-void
-set_navigation_state_changed()
-{
- navigation_state_changed = true;
+ return ret;
}
/**
-* 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)
+ * Check failsafe and main status and set navigation status for navigator accordingly
+ */
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished)
{
- bool valid_transition = false;
- int ret = ERROR;
-
- warnx("Current state: %d, requested state: %d", current_status->hil_state, new_state);
+ navigation_state_t nav_state_old = status->nav_state;
+
+ bool armed = (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR);
+ status->failsafe = false;
+
+ /* evaluate main state to decide in normal (non-failsafe) mode */
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ case MAIN_STATE_MANUAL:
+ case MAIN_STATE_ALTCTL:
+ case MAIN_STATE_POSCTL:
+ /* require RC for all manual modes */
+ if (status->rc_signal_lost && armed) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- if (current_status->hil_state == new_state) {
- warnx("Hil state not changed");
- valid_transition = true;
+ } else {
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ status->nav_state = NAVIGATION_STATE_ACRO;
+ break;
+
+ case MAIN_STATE_MANUAL:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+
+ case MAIN_STATE_ALTCTL:
+ status->nav_state = NAVIGATION_STATE_ALTCTL;
+ break;
+
+ case MAIN_STATE_POSCTL:
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ break;
+
+ default:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+ }
+ }
+ break;
+
+ case MAIN_STATE_AUTO_MISSION:
+ /* go into failsafe
+ * - if either the datalink is enabled and lost as well as RC is lost
+ * - if there is no datalink and the mission is finished */
+ if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
+ (!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- } else {
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- switch (new_state) {
+ /* don't bother if RC is lost and mission is not yet finished */
+ } else if (status->rc_signal_lost) {
- case HIL_STATE_OFF:
+ /* this mode is ok, we don't need RC for missions */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ }
+ break;
+
+ case MAIN_STATE_AUTO_LOITER:
+ /* go into failsafe if datalink and RC is lost */
+ if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- /* we're in HIL and unexpected things can happen if we disable HIL now */
- mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
- valid_transition = false;
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- break;
+ /* go into failsafe if RC is lost and datalink loss is not set up */
+ } else if (status->rc_signal_lost && !data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- case HIL_STATE_ON:
+ /* don't bother if RC is lost if datalink is connected */
+ } else if (status->rc_signal_lost) {
- if (current_status->arming_state == ARMING_STATE_INIT
- || current_status->arming_state == ARMING_STATE_STANDBY
- || current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
+ /* this mode is ok, we don't need RC for loitering */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ }
+ break;
+
+ case MAIN_STATE_AUTO_RTL:
+ /* require global position and home */
+ if ((!status->condition_global_position_valid || !status->condition_home_position_valid)) {
+ status->failsafe = true;
+
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+ } else {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ }
+ break;
- current_control_mode->flag_system_hil_enabled = true;
- mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
- valid_transition = true;
+ default:
+ break;
+ }
- // Disable publication of all attached sensors
+ return status->nav_state != nav_state_old;
+}
- /* list directory */
- DIR *d;
- struct dirent *direntry;
- d = opendir("/dev");
- if (d) {
+int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
+{
+ int ret;
- while ((direntry = readdir(d)) != NULL) {
+ int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
- int sensfd = ::open(direntry->d_name, 0);
- int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0);
- close(sensfd);
+ if (fd < 0) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL SENSOR MISSING");
+ ret = fd;
+ goto system_eval;
+ }
- printf("Disabling %s\n: %s", direntry->d_name, (!block_ret) ? "OK" : "FAIL");
- }
+ ret = ioctl(fd, ACCELIOCSELFTEST, 0);
- closedir(d);
+ if (ret != OK) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL CALIBRATION");
+ goto system_eval;
+ }
- warnx("directory listing ok (FS mounted and readable)");
+ /* check measurement result range */
+ struct accel_report acc;
+ ret = read(fd, &acc, sizeof(acc));
- } else {
- /* failed opening dir */
- warnx("FAILED LISTING DEVICE ROOT DIRECTORY");
- return 1;
- }
- }
+ if (ret == sizeof(acc)) {
+ /* evaluate values */
+ float accel_scale = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
- break;
+ if (accel_scale < 9.78f || accel_scale > 9.83f) {
+ mavlink_log_info(mavlink_fd, "#audio: Accelerometer calibration recommended.");
+ }
- default:
- warnx("Unknown hil state");
- break;
+ if (accel_scale > 30.0f /* m/s^2 */) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL RANGE");
+ /* this is frickin' fatal */
+ ret = ERROR;
+ goto system_eval;
+ } else {
+ ret = OK;
}
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL READ");
+ /* this is frickin' fatal */
+ ret = ERROR;
+ goto system_eval;
}
- if (valid_transition) {
- current_status->hil_state = new_state;
+ if (!status->is_rotary_wing) {
+ fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
- current_status->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
+ if (fd < 0) {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING");
+ ret = fd;
+ goto system_eval;
+ }
- current_control_mode->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, current_control_mode);
+ struct differential_pressure_s diff_pres;
- // XXX also set lockdown here
+ ret = read(fd, &diff_pres, sizeof(diff_pres));
- ret = OK;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
+ if (ret == sizeof(diff_pres)) {
+ if (fabsf(diff_pres.differential_pressure_filtered_pa > 5.0f)) {
+ mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING");
+ // XXX do not make this fatal yet
+ ret = OK;
+ }
+ } else {
+ mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED READ");
+ /* this is frickin' fatal */
+ ret = ERROR;
+ goto system_eval;
+ }
}
+system_eval:
+ close(fd);
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;
-//}
-