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.cpp42
1 files changed, 26 insertions, 16 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 3cef10185..490fc8fc6 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -67,7 +67,9 @@ 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)
+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)
{
/*
* Perform an atomic state update
@@ -82,6 +84,13 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
} else {
+ /* enforce lockdown in HIL */
+ if (control_mode->flag_system_hil_enabled) {
+ armed->lockdown = true;
+ } else {
+ armed->lockdown = false;
+ }
+
switch (new_arming_state) {
case ARMING_STATE_INIT:
@@ -98,7 +107,8 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* allow coming from INIT and disarming from ARMED */
if (status->arming_state == ARMING_STATE_INIT
- || status->arming_state == ARMING_STATE_ARMED) {
+ || 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) {
@@ -115,7 +125,7 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s *
/* 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 */
+ && (!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;
@@ -228,8 +238,9 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m
case MAIN_STATE_SEATBELT:
- /* need altitude estimate */
- if (current_state->condition_local_altitude_valid) {
+ /* need at minimum altitude estimate */
+ if (current_state->condition_local_altitude_valid ||
+ current_state->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
}
@@ -237,8 +248,9 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m
case MAIN_STATE_EASY:
- /* need local position estimate */
- if (current_state->condition_local_position_valid) {
+ /* need at minimum local position estimate */
+ if (current_state->condition_local_position_valid ||
+ current_state->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
}
@@ -464,20 +476,17 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
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;
- }
+ /* 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;
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
+ || current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
current_control_mode->flag_system_hil_enabled = true;
mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
@@ -495,13 +504,14 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
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);
+ // XXX also set lockdown here
+
ret = OK;
} else {