commander status reuse arming_state_names in state_machine_helper (#8667)

This commit is contained in:
SungTae Moon
2018-01-28 00:22:29 +09:00
committed by Daniel Agar
parent 1f5d6c7117
commit f8f95078e8
3 changed files with 6 additions and 50 deletions
+1 -47
View File
@@ -647,55 +647,9 @@ void print_status()
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f, yaw: %.2f", _home.lat, _home.lon, (double)_home.alt, (double)_home.yaw);
warnx("home: x = %.7f, y = %.7f, z = %.2f ", (double)_home.x, (double)_home.y, (double)_home.z);
warnx("datalink: %s", (status.data_link_lost) ? "LOST" : "OK");
warnx("main state: %d", internal_state.main_state);
warnx("nav state: %d", status.nav_state);
/* 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 (status.arming_state) {
case vehicle_status_s::ARMING_STATE_INIT:
armed_str = "INIT";
break;
case vehicle_status_s::ARMING_STATE_STANDBY:
armed_str = "STANDBY";
break;
case vehicle_status_s::ARMING_STATE_ARMED:
armed_str = "ARMED";
break;
case vehicle_status_s::ARMING_STATE_ARMED_ERROR:
armed_str = "ARMED_ERROR";
break;
case vehicle_status_s::ARMING_STATE_STANDBY_ERROR:
armed_str = "STANDBY_ERROR";
break;
case vehicle_status_s::ARMING_STATE_REBOOT:
armed_str = "REBOOT";
break;
case vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE:
armed_str = "IN_AIR_RESTORE";
break;
default:
armed_str = "ERR: UNKNOWN STATE";
break;
}
px4_close(state_sub);
warnx("arming: %s", armed_str);
warnx("arming: %s", arming_state_names[status.arming_state]);
}
static orb_advert_t status_pub;
@@ -93,7 +93,7 @@ static const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle
};
// You can index into the array with an arming_state_t in order to get its textual representation
static const char *const state_names[vehicle_status_s::ARMING_STATE_MAX] = {
const char *const arming_state_names[vehicle_status_s::ARMING_STATE_MAX] = {
"ARMING_STATE_INIT",
"ARMING_STATE_STANDBY",
"ARMING_STATE_ARMED",
@@ -374,8 +374,8 @@ transition_result_t arming_state_transition(vehicle_status_s *status,
if (ret == TRANSITION_DENIED) {
/* print to MAVLink and console if we didn't provide any feedback yet */
if (!feedback_provided) {
mavlink_log_critical(mavlink_log_pub, "TRANSITION_DENIED: %s - %s", state_names[status->arming_state],
state_names[new_arming_state]);
mavlink_log_critical(mavlink_log_pub, "TRANSITION_DENIED: %s - %s", arming_state_names[status->arming_state],
arming_state_names[new_arming_state]);
}
}
@@ -108,6 +108,8 @@ struct status_flags_s {
bool gps_failure; // Set to true if a gps failure is detected
};
extern const char *const arming_state_names[];
bool is_safe(const struct safety_s *safety, const struct actuator_armed_s *armed);
transition_result_t arming_state_transition(struct vehicle_status_s *status,