aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.cpp
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-05-16 12:12:43 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-05-16 12:12:43 +0200
commit8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af (patch)
treeea6f3edcfa749eb5b0dcc7f307b0fa490d579617 /src/modules/commander/state_machine_helper.cpp
parentd2553bfd2930eb02664d564559fa361b80c63f61 (diff)
parentf892a7278a4f452c12678fe00c6ff28c2354d548 (diff)
downloadpx4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.tar.gz
px4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.tar.bz2
px4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.zip
Merge branch 'master' into offboard2
Diffstat (limited to 'src/modules/commander/state_machine_helper.cpp')
-rw-r--r--src/modules/commander/state_machine_helper.cpp173
1 files changed, 84 insertions, 89 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 9cecf5371..aaabde66b 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -69,10 +69,44 @@ static bool arming_state_changed = true;
static bool main_state_changed = true;
static bool failsafe_state_changed = true;
+// This array defines the arming state transitions. The rows are the new state, and the columns
+// are the current state. Using new state and current state you can index into the array which
+// will be true for a valid transition or false for a invalid transition. In some cases even
+// though the transition is marked as true additional checks must be made. See arming_state_transition
+// code for those checks.
+static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+};
+
+// You can index into the array with an arming_state_t in order to get it's textual representation
+static const char *state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
+};
+
transition_result_t
-arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety,
- arming_state_t new_arming_state, struct actuator_armed_s *armed)
+arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
+
/*
* Perform an atomic state update
*/
@@ -85,7 +119,6 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
ret = TRANSITION_NOT_CHANGED;
} else {
-
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
@@ -94,95 +127,43 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
armed->lockdown = false;
}
- switch (new_arming_state) {
- case ARMING_STATE_INIT:
-
- /* allow going back from INIT for calibration */
- if (status->arming_state == ARMING_STATE_STANDBY) {
- ret = TRANSITION_CHANGED;
- armed->armed = false;
- armed->ready_to_arm = false;
- }
-
- break;
-
- case ARMING_STATE_STANDBY:
-
- /* allow coming from INIT and disarming from ARMED */
- if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED
- || status->hil_state == HIL_STATE_ON) {
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
+
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ // Fail transition if we need safety switch press
+ // Allow if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first.");
+ }
- /* 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;
+ valid_transition = false;
}
- }
-
- break;
-
- case ARMING_STATE_ARMED:
- /* allow arming from STANDBY and IN-AIR-RESTORE */
- if ((status->arming_state == ARMING_STATE_STANDBY
- || status->arming_state == ARMING_STATE_IN_AIR_RESTORE)
- && (!safety->safety_switch_available || safety->safety_off || status->hil_state == HIL_STATE_ON)) { /* only allow arming if safety is off */
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = true;
- }
-
- break;
-
- case ARMING_STATE_ARMED_ERROR:
-
- /* an armed error happens when ARMED obviously */
- if (status->arming_state == ARMING_STATE_ARMED) {
- ret = TRANSITION_CHANGED;
- armed->armed = true;
- armed->ready_to_arm = false;
+ } 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_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;
+ // 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;
}
@@ -191,8 +172,15 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* end of atomic state update */
irqrestore(flags);
- if (ret == TRANSITION_DENIED)
- warnx("arming transition rejected");
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "Invalid arming transition from %s to %s";
+
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
+
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
@@ -234,7 +222,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ALTCTL:
/* need at minimum altitude estimate */
if (!status->is_rotary_wing ||
@@ -245,7 +233,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
@@ -266,7 +254,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
case MAIN_STATE_OFFBOARD:
- /* need global position estimate */
+ /* need offboard signal */
if (!status->offboard_control_signal_lost) {
ret = TRANSITION_CHANGED;
}
@@ -351,6 +339,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
/* list directory */
DIR *d;
d = opendir("/dev");
+
if (d) {
struct dirent *direntry;
@@ -362,26 +351,32 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
if (!strncmp("tty", direntry->d_name, 3)) {
continue;
}
+
/* skip mtd devices */
if (!strncmp("mtd", direntry->d_name, 3)) {
continue;
}
+
/* skip ram devices */
if (!strncmp("ram", direntry->d_name, 3)) {
continue;
}
+
/* skip MMC devices */
if (!strncmp("mmc", direntry->d_name, 3)) {
continue;
}
+
/* skip mavlink */
if (!strcmp("mavlink", direntry->d_name)) {
continue;
}
+
/* skip console */
if (!strcmp("console", direntry->d_name)) {
continue;
}
+
/* skip null */
if (!strcmp("null", direntry->d_name)) {
continue;