aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.c
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-07-15 22:15:15 +0200
committerJulian Oes <julian@oes.ch>2013-07-15 22:15:15 +0200
commit1b38cf715d85b15f2200d49b64fbe22a05b71937 (patch)
tree1df1db43a7ac8dad47d96059eef8efff65b6248d /src/modules/commander/state_machine_helper.c
parentbf2ff98856b7e6b107a7ec5bbde3b00e38713804 (diff)
downloadpx4-firmware-1b38cf715d85b15f2200d49b64fbe22a05b71937.tar.gz
px4-firmware-1b38cf715d85b15f2200d49b64fbe22a05b71937.tar.bz2
px4-firmware-1b38cf715d85b15f2200d49b64fbe22a05b71937.zip
Renamed actuator_safety back to actuator_armed, compiling but untested
Diffstat (limited to 'src/modules/commander/state_machine_helper.c')
-rw-r--r--src/modules/commander/state_machine_helper.c26
1 files changed, 13 insertions, 13 deletions
diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c
index c15fc91a0..0b241d108 100644
--- a/src/modules/commander/state_machine_helper.c
+++ b/src/modules/commander/state_machine_helper.c
@@ -57,7 +57,7 @@
#include "commander_helper.h"
-int arming_state_transition(int status_pub, struct vehicle_status_s *current_state, arming_state_t new_arming_state, int safety_pub, struct actuator_safety_s *safety, const int mavlink_fd) {
+int arming_state_transition(int status_pub, struct vehicle_status_s *current_state, arming_state_t new_arming_state, int armed_pub, struct actuator_armed_s *armed, const int mavlink_fd) {
int ret = ERROR;
@@ -73,8 +73,8 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
/* allow going back from INIT for calibration */
if (current_state->arming_state == ARMING_STATE_STANDBY) {
ret = OK;
- safety->armed = false;
- safety->ready_to_arm = false;
+ armed->armed = false;
+ armed->ready_to_arm = false;
}
break;
case ARMING_STATE_STANDBY:
@@ -86,8 +86,8 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
/* sensors need to be initialized for STANDBY state */
if (current_state->condition_system_sensors_initialized) {
ret = OK;
- safety->armed = false;
- safety->ready_to_arm = true;
+ armed->armed = false;
+ armed->ready_to_arm = true;
} else {
mavlink_log_critical(mavlink_fd, "Rej. STANDBY state, sensors not initialized");
}
@@ -101,7 +101,7 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
/* XXX conditions for arming? */
ret = OK;
- safety->armed = true;
+ armed->armed = true;
}
break;
case ARMING_STATE_ARMED_ERROR:
@@ -111,7 +111,7 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
/* XXX conditions for an error state? */
ret = OK;
- safety->armed = true;
+ armed->armed = true;
}
break;
case ARMING_STATE_STANDBY_ERROR:
@@ -120,8 +120,8 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
|| current_state->arming_state == ARMING_STATE_INIT
|| current_state->arming_state == ARMING_STATE_ARMED_ERROR) {
ret = OK;
- safety->armed = false;
- safety->ready_to_arm = false;
+ armed->armed = false;
+ armed->ready_to_arm = false;
}
break;
case ARMING_STATE_REBOOT:
@@ -132,8 +132,8 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
|| current_state->arming_state == ARMING_STATE_STANDBY_ERROR) {
ret = OK;
- safety->armed = false;
- safety->ready_to_arm = false;
+ armed->armed = false;
+ armed->ready_to_arm = false;
}
break;
@@ -151,8 +151,8 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
current_state->timestamp = hrt_absolute_time();
orb_publish(ORB_ID(vehicle_status), status_pub, current_state);
- safety->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(actuator_safety), safety_pub, safety);
+ armed->timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(actuator_armed), armed_pub, armed);
}
}