aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/commander/commander.c109
-rw-r--r--apps/commander/state_machine_helper.c26
-rw-r--r--apps/drivers/blinkm/blinkm.cpp2
-rw-r--r--apps/drivers/px4io/px4io.cpp13
-rw-r--r--apps/mavlink/mavlink.c4
-rw-r--r--apps/mavlink_onboard/mavlink.c2
-rw-r--r--apps/multirotor_att_control/multirotor_att_control_main.c7
-rw-r--r--apps/uORB/topics/vehicle_status.h43
8 files changed, 103 insertions, 103 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index 94e344da1..2fdcf4ce3 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -323,8 +323,8 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
{
/* set to mag calibration mode */
- status->flag_preflight_mag_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_mag_calibration = true;
+ // state_machine_publish(status_pub, status, mavlink_fd);
int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
struct mag_report mag;
@@ -559,8 +559,8 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
}
/* disable calibration mode */
- status->flag_preflight_mag_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_mag_calibration = false;
+ // state_machine_publish(status_pub, status, mavlink_fd);
close(sub_mag);
}
@@ -568,8 +568,8 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status)
void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
{
/* set to gyro calibration mode */
- status->flag_preflight_gyro_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_gyro_calibration = true;
+ // state_machine_publish(status_pub, status, mavlink_fd);
const int calibration_count = 5000;
@@ -621,8 +621,8 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
gyro_offset[2] = gyro_offset[2] / calibration_count;
/* exit gyro calibration mode */
- status->flag_preflight_gyro_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_gyro_calibration = false;
+ // state_machine_publish(status_pub, status, mavlink_fd);
if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
@@ -679,8 +679,8 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status)
mavlink_log_info(mavlink_fd, "keep it level and still");
/* set to accel calibration mode */
- status->flag_preflight_accel_calibration = true;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_accel_calibration = true;
+ // state_machine_publish(status_pub, status, mavlink_fd);
const int calibration_count = 2500;
@@ -787,8 +787,8 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status)
}
/* exit accel calibration mode */
- status->flag_preflight_accel_calibration = false;
- state_machine_publish(status_pub, status, mavlink_fd);
+ // status->flag_preflight_accel_calibration = false;
+ // state_machine_publish(status_pub, status, mavlink_fd);
close(sub_sensor_combined);
}
@@ -1022,7 +1022,7 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta
break;
case VEHICLE_CMD_PREFLIGHT_STORAGE: {
- if (current_status.flag_system_armed &&
+ if (current_status.flag_fmu_armed &&
((current_status.system_type == VEHICLE_TYPE_QUADROTOR) ||
(current_status.system_type == VEHICLE_TYPE_HEXAROTOR) ||
(current_status.system_type == VEHICLE_TYPE_OCTOROTOR))) {
@@ -1327,7 +1327,8 @@ int commander_thread_main(int argc, char *argv[])
current_status.navigation_state = NAVIGATION_STATE_INIT;
current_status.arming_state = ARMING_STATE_INIT;
current_status.hil_state = HIL_STATE_OFF;
- current_status.flag_system_armed = false;
+ current_status.flag_fmu_armed = false;
+ current_status.flag_io_armed = false; // XXX read this from somewhere
/* neither manual nor offboard control commands have been received */
current_status.offboard_control_signal_found_once = false;
@@ -1341,13 +1342,13 @@ int commander_thread_main(int argc, char *argv[])
current_status.flag_external_manual_override_ok = true;
/* flag position info as bad, do not allow auto mode */
- current_status.flag_vector_flight_mode_ok = false;
+ // current_status.flag_vector_flight_mode_ok = false;
/* set battery warning flag */
current_status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
// XXX for now just set sensors as initialized
- current_status.flag_system_sensors_initialized = true;
+ current_status.condition_system_sensors_initialized = true;
/* advertise to ORB */
stat_pub = orb_advertise(ORB_ID(vehicle_status), &current_status);
@@ -1501,7 +1502,7 @@ int commander_thread_main(int argc, char *argv[])
/* update parameters */
- if (!current_status.flag_system_armed) {
+ if (!current_status.flag_fmu_armed) {
if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
warnx("failed setting new system type");
}
@@ -1654,7 +1655,7 @@ int commander_thread_main(int argc, char *argv[])
/* If in INIT state, try to proceed to STANDBY state */
if (current_status.arming_state == ARMING_STATE_INIT) {
// XXX fix for now
- current_status.flag_system_sensors_initialized = true;
+ current_status.condition_system_sensors_initialized = true;
arming_state_transition(stat_pub, &current_status, ARMING_STATE_STANDBY, mavlink_fd);
} else {
// XXX: Add emergency stuff if sensors are lost
@@ -1671,45 +1672,45 @@ int commander_thread_main(int argc, char *argv[])
*/
/* store current state to reason later about a state change */
- bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
- bool global_pos_valid = current_status.flag_global_position_valid;
- bool local_pos_valid = current_status.flag_local_position_valid;
+ // bool vector_flight_mode_ok = current_status.flag_vector_flight_mode_ok;
+ bool global_pos_valid = current_status.condition_global_position_valid;
+ bool local_pos_valid = current_status.condition_local_position_valid;
/* check for global or local position updates, set a timeout of 2s */
if (hrt_absolute_time() - last_global_position_time < 2000000) {
- current_status.flag_global_position_valid = true;
+ current_status.condition_global_position_valid = true;
// XXX check for controller status and home position as well
} else {
- current_status.flag_global_position_valid = false;
+ current_status.condition_global_position_valid = false;
}
if (hrt_absolute_time() - last_local_position_time < 2000000) {
- current_status.flag_local_position_valid = true;
+ current_status.condition_local_position_valid = true;
// XXX check for controller status and home position as well
} else {
- current_status.flag_local_position_valid = false;
+ current_status.condition_local_position_valid = false;
}
/*
* Consolidate global position and local position valid flags
* for vector flight mode.
*/
- if (current_status.flag_local_position_valid ||
- current_status.flag_global_position_valid) {
- current_status.flag_vector_flight_mode_ok = true;
+ // if (current_status.condition_local_position_valid ||
+ // current_status.condition_global_position_valid) {
+ // current_status.flag_vector_flight_mode_ok = true;
- } else {
- current_status.flag_vector_flight_mode_ok = false;
- }
+ // } else {
+ // current_status.flag_vector_flight_mode_ok = false;
+ // }
- /* consolidate state change, flag as changed if required */
- if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok ||
- global_pos_valid != current_status.flag_global_position_valid ||
- local_pos_valid != current_status.flag_local_position_valid) {
- state_changed = true;
- }
+ // /* consolidate state change, flag as changed if required */
+ // if (vector_flight_mode_ok != current_status.flag_vector_flight_mode_ok ||
+ // global_pos_valid != current_status.flag_global_position_valid ||
+ // local_pos_valid != current_status.flag_local_position_valid) {
+ // state_changed = true;
+ // }
/*
* Mark the position of the first position lock as return to launch (RTL)
@@ -1721,16 +1722,16 @@ int commander_thread_main(int argc, char *argv[])
* 2) The system has not aquired position lock before
* 3) The system is not armed (on the ground)
*/
- if (!current_status.flag_valid_launch_position &&
- !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
- !current_status.flag_system_armed) {
- /* first time a valid position, store it and emit it */
-
- // XXX implement storage and publication of RTL position
- current_status.flag_valid_launch_position = true;
- current_status.flag_auto_flight_mode_ok = true;
- state_changed = true;
- }
+ // if (!current_status.flag_valid_launch_position &&
+ // !vector_flight_mode_ok && current_status.flag_vector_flight_mode_ok &&
+ // !current_status.flag_system_armed) {
+ // first time a valid position, store it and emit it
+
+ // // XXX implement storage and publication of RTL position
+ // current_status.flag_valid_launch_position = true;
+ // current_status.flag_auto_flight_mode_ok = true;
+ // state_changed = true;
+ // }
if (orb_check(gps_sub, &new_data)) {
@@ -1760,7 +1761,7 @@ int commander_thread_main(int argc, char *argv[])
&& (vdop_m < vdop_threshold_m) // XXX note that vdop is 0 for mtk
&& !home_position_set
&& (hrt_absolute_time() - gps_position.timestamp_position < 2000000)
- && !current_status.flag_system_armed) {
+ && !current_status.flag_fmu_armed) {
warnx("setting home position");
/* copy position data to uORB home message, store it locally as well */
@@ -1876,7 +1877,7 @@ int commander_thread_main(int argc, char *argv[])
if (navigation_state_transition(stat_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, mavlink_fd) != OK) {
// These is not supposed to happen
- warnx("ERROR: Navigation state MANUAL_STANDBY rejected 1");
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
}
/* Try seatbelt or fallback to manual */
@@ -1886,7 +1887,7 @@ int commander_thread_main(int argc, char *argv[])
// fallback to MANUAL_STANDBY
if (navigation_state_transition(stat_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, mavlink_fd) != OK) {
// These is not supposed to happen
- warnx("ERROR: Navigation state MANUAL_STANDBY rejected 2");
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
}
}
@@ -1899,7 +1900,7 @@ int commander_thread_main(int argc, char *argv[])
// or fallback to MANUAL_STANDBY
if (navigation_state_transition(stat_pub, &current_status, NAVIGATION_STATE_MANUAL_STANDBY, mavlink_fd) != OK) {
// These is not supposed to happen
- warnx("ERROR: Navigation state MANUAL_STANDBY rejected 3");
+ warnx("ERROR: Navigation state MANUAL_STANDBY rejected");
}
}
}
@@ -2047,7 +2048,6 @@ int commander_thread_main(int argc, char *argv[])
// ) &&
if ((sp_man.yaw < -STICK_ON_OFF_LIMIT) && (sp_man.throttle < STICK_THRUST_RANGE * 0.2f)) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- printf("Try disarm\n");
arming_state_transition(stat_pub, &current_status, ARMING_STATE_STANDBY, mavlink_fd);
stick_off_counter = 0;
@@ -2060,7 +2060,6 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position --> arm */
if (sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.2f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- printf("Try arm\n");
arming_state_transition(stat_pub, &current_status, ARMING_STATE_ARMED, mavlink_fd);
stick_on_counter = 0;
@@ -2156,13 +2155,13 @@ int commander_thread_main(int argc, char *argv[])
current_status.offboard_control_signal_lost_interval = 0;
/* arm / disarm on request */
- if (sp_offboard.armed && !current_status.flag_system_armed) {
+ if (sp_offboard.armed && !current_status.flag_fmu_armed) {
#warning fix this
// update_state_machine_arm(stat_pub, &current_status, mavlink_fd);
/* switch to stabilized mode = takeoff */
// update_state_machine_mode_stabilized(stat_pub, &current_status, mavlink_fd);
- } else if (!sp_offboard.armed && current_status.flag_system_armed) {
+ } else if (!sp_offboard.armed && current_status.flag_fmu_armed) {
// update_state_machine_disarm(stat_pub, &current_status, mavlink_fd);
}
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c
index ae7f2a1c1..61ebe8c16 100644
--- a/apps/commander/state_machine_helper.c
+++ b/apps/commander/state_machine_helper.c
@@ -278,7 +278,7 @@ int arming_state_transition(int status_pub, struct vehicle_status_s *current_sta
|| current_state->arming_state == ARMING_STATE_ARMED) {
/* sensors need to be initialized for STANDBY state */
- if (current_state->flag_system_sensors_initialized) {
+ if (current_state->condition_system_sensors_initialized) {
ret = OK;
} else {
mavlink_log_critical(mavlink_fd, "Rej. STANDBY state, sensors not initialized");
@@ -392,7 +392,7 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
/* need to be disarmed and have a position estimate */
if (current_state->arming_state != ARMING_STATE_STANDBY) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_STANDBY: not disarmed");
- } else if (!current_state->flag_local_position_valid) {
+ } else if (!current_state->condition_local_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_STANDBY: no position estimate");
} else {
ret = OK;
@@ -416,7 +416,7 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
/* need to be armed and have a position estimate */
if (current_state->arming_state != ARMING_STATE_ARMED) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT: not armed");
- } else if (!current_state->flag_local_position_valid) {
+ } else if (!current_state->condition_local_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT: no pos estimate");
} else {
ret = OK;
@@ -439,7 +439,7 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
/* need to be armed and have a position estimate */
if (current_state->arming_state != ARMING_STATE_ARMED) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_DESCENT: not armed");
- } else if (!current_state->flag_local_position_valid) {
+ } else if (!current_state->condition_local_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. SEATBELT_DESCENT: no pos estimate");
} else {
ret = OK;
@@ -458,9 +458,9 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
/* need to be disarmed and have a position and home lock */
if (current_state->arming_state != ARMING_STATE_STANDBY) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: not disarmed");
- } else if (!current_state->flag_global_position_valid) {
+ } else if (!current_state->condition_global_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: no pos lock");
- } else if (!current_state->flag_valid_home_position) {
+ } else if (!current_state->condition_home_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_STANDBY: no home pos");
} else {
ret = OK;
@@ -504,9 +504,9 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
|| current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
/* need to have a position and home lock */
- if (!current_state->flag_global_position_valid) {
+ if (!current_state->condition_global_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_LOITER: no pos lock");
- } else if (!current_state->flag_valid_home_position) {
+ } else if (!current_state->condition_home_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_LOITER: no home pos");
} else {
ret = OK;
@@ -524,7 +524,7 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
|| current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
/* need to have a mission ready */
- if (!current_state->flag_auto_mission_available) {
+ if (!current_state-> condition_auto_mission_available) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_MISSION: no mission available");
} else {
ret = OK;
@@ -542,9 +542,9 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
|| current_state->navigation_state == NAVIGATION_STATE_MANUAL) {
/* need to have a position and home lock */
- if (!current_state->flag_global_position_valid) {
+ if (!current_state->condition_global_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_RTL: no pos lock");
- } else if (!current_state->flag_valid_home_position) {
+ } else if (!current_state->condition_home_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_RTL: no home pos");
} else {
ret = OK;
@@ -559,9 +559,9 @@ int navigation_state_transition(int status_pub, struct vehicle_status_s *current
|| current_state->navigation_state == NAVIGATION_STATE_AUTO_LOITER) {
/* need to have a position and home lock */
- if (!current_state->flag_global_position_valid) {
+ if (!current_state->condition_global_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_LAND: no pos lock");
- } else if (!current_state->flag_valid_home_position) {
+ } else if (!current_state->condition_home_position_valid) {
mavlink_log_critical(mavlink_fd, "Rej. AUTO_LAND: no home pos");
} else {
ret = OK;
diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp
index 6aff27e4c..ceb2d987d 100644
--- a/apps/drivers/blinkm/blinkm.cpp
+++ b/apps/drivers/blinkm/blinkm.cpp
@@ -529,7 +529,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_system_armed == false) {
+ if(vehicle_status_raw.flag_fmu_armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index adb894371..99f0f35b2 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -446,7 +446,7 @@ PX4IO::init()
}
/* keep waiting for state change for 10 s */
- } while (!status.flag_system_armed);
+ } while (!status.flag_fmu_armed);
/* regular boot, no in-air restart, init IO */
} else {
@@ -658,11 +658,12 @@ PX4IO::io_set_arming_state()
} else {
clear |= PX4IO_P_SETUP_ARMING_ARM_OK;
}
- if (vstatus.flag_vector_flight_mode_ok) {
- set |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK;
- } else {
- clear |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK;
- }
+ // TODO fix this
+ // if (vstatus.flag_vector_flight_mode_ok) {
+ // set |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK;
+ // } else {
+ // clear |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK;
+ // }
if (vstatus.flag_external_manual_override_ok) {
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
} else {
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index 34b267d56..342328728 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -246,9 +246,7 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_mode)
**/
/* set calibration state */
- if (v_status.flag_preflight_gyro_calibration ||
- v_status.flag_preflight_mag_calibration ||
- v_status.flag_preflight_accel_calibration) {
+ if (v_status.flag_preflight_calibration) {
*mavlink_state = MAV_STATE_CALIBRATING;
diff --git a/apps/mavlink_onboard/mavlink.c b/apps/mavlink_onboard/mavlink.c
index c5a1e82a8..fbfce7dc9 100644
--- a/apps/mavlink_onboard/mavlink.c
+++ b/apps/mavlink_onboard/mavlink.c
@@ -290,7 +290,7 @@ get_mavlink_mode_and_state(const struct vehicle_status_s *v_status, const struct
}
/* set arming state */
- if (v_status->flag_system_armed) {
+ if (v_status->flag_fmu_armed) {
*mavlink_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
} else {
*mavlink_mode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/apps/multirotor_att_control/multirotor_att_control_main.c
index da7550f79..79ca9fe2d 100644
--- a/apps/multirotor_att_control/multirotor_att_control_main.c
+++ b/apps/multirotor_att_control/multirotor_att_control_main.c
@@ -247,7 +247,7 @@ mc_thread_main(int argc, char *argv[])
/* initialize to current yaw if switching to manual or att control */
if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
state.flag_control_manual_enabled != flag_control_manual_enabled ||
- state.flag_system_armed != flag_system_armed) {
+ state.flag_fmu_armed != flag_system_armed) {
att_sp.yaw_body = att.yaw;
}
@@ -291,7 +291,7 @@ mc_thread_main(int argc, char *argv[])
att_sp.pitch_body = manual.pitch;
/* set attitude if arming */
- if (!flag_control_attitude_enabled && state.flag_system_armed) {
+ if (!flag_control_attitude_enabled && state.flag_fmu_armed) {
att_sp.yaw_body = att.yaw;
}
@@ -395,7 +395,8 @@ mc_thread_main(int argc, char *argv[])
/* update state */
flag_control_attitude_enabled = state.flag_control_attitude_enabled;
flag_control_manual_enabled = state.flag_control_manual_enabled;
- flag_system_armed = state.flag_system_armed;
+ flag_system_armed = state.flag_fmu_armed;
+ // XXX add some logic to this
perf_end(mc_loop_perf);
} /* end of poll call for attitude updates */
diff --git a/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
index 495542244..eba5a5047 100644
--- a/apps/uORB/topics/vehicle_status.h
+++ b/apps/uORB/topics/vehicle_status.h
@@ -183,31 +183,35 @@ struct vehicle_status_s
return_switch_pos_t return_switch;
mission_switch_pos_t mission_switch;
+
+ bool condition_system_emergency;
+ bool condition_system_in_air_restore; /**< true if we can restore in mid air */
+ bool condition_system_sensors_initialized;
+ bool condition_system_returned_to_home;
+ bool condition_auto_mission_available;
+ bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
+ bool condition_launch_position_valid; /**< indicates a valid launch position */
+ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool condition_local_position_valid;
- bool flag_system_armed; /**< true is motors / actuators are armed */
+ bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
+ bool flag_fmu_armed; /**< true is motors / actuators of FMU are armed */
+ bool flag_io_armed; /**< true is motors / actuators of IO are armed */
bool flag_system_emergency;
- bool flag_system_in_air_restore; /**< true if we can restore in mid air */
- bool flag_system_sensors_initialized;
- bool flag_system_arming_requested;
- bool flag_system_disarming_requested;
- bool flag_system_reboot_requested;
- bool flag_system_returned_to_home;
-
- bool flag_auto_mission_available;
- bool flag_auto_enabled;
+ bool flag_preflight_calibration;
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
bool flag_control_offboard_enabled; /**< true if offboard control input is on */
- bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
-
+ bool flag_auto_enabled;
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
bool flag_control_velocity_enabled; /**< true if speed (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
- bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
- bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
- bool flag_preflight_accel_calibration;
+
+ // bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
+ // bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
+ // bool flag_preflight_accel_calibration;
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception is terminally lost */
@@ -238,13 +242,10 @@ struct vehicle_status_s
uint16_t errors_count3;
uint16_t errors_count4;
- bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
- bool flag_local_position_valid;
- bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
- bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
+ // bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
+ // bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
- bool flag_valid_launch_position; /**< indicates a valid launch position */
- bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+
};
/**