forked from Archive/PX4-Autopilot
commander: failsafe_state removed, replaced with bool failsafe, navigation state and failsafe determined directly from main state and conditions
This commit is contained in:
parent
91f0b9eee4
commit
e0ed0625f8
|
@ -77,6 +77,7 @@
|
|||
#include <uORB/topics/differential_pressure.h>
|
||||
#include <uORB/topics/safety.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
#include <uORB/topics/telemetry_status.h>
|
||||
|
||||
#include <drivers/drv_led.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
@ -122,6 +123,7 @@ extern struct system_load_s system_load;
|
|||
#define POSITION_TIMEOUT (600 * 1000) /**< consider the local or global position estimate invalid after 600ms */
|
||||
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
|
||||
#define RC_TIMEOUT 500000
|
||||
#define DL_TIMEOUT 5 * 1000* 1000
|
||||
#define DIFFPRESS_TIMEOUT 2000000
|
||||
|
||||
#define PRINT_INTERVAL 5000000
|
||||
|
@ -495,12 +497,12 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
|||
unsigned int mav_goto = cmd->param1;
|
||||
|
||||
if (mav_goto == 0) { // MAV_GOTO_DO_HOLD
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_LOITER;
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: pause mission cmd");
|
||||
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
} else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
mavlink_log_critical(mavlink_fd, "#audio: continue mission cmd");
|
||||
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
|
@ -639,13 +641,6 @@ int commander_thread_main(int argc, char *argv[])
|
|||
arming_states_str[5] = "REBOOT";
|
||||
arming_states_str[6] = "IN_AIR_RESTORE";
|
||||
|
||||
char *failsafe_states_str[FAILSAFE_STATE_MAX];
|
||||
failsafe_states_str[0] = "NORMAL";
|
||||
failsafe_states_str[1] = "RTL_RC";
|
||||
failsafe_states_str[2] = "RTL_DL";
|
||||
failsafe_states_str[3] = "LAND";
|
||||
failsafe_states_str[4] = "TERMINATION";
|
||||
|
||||
/* pthread for slow low prio thread */
|
||||
pthread_t commander_low_prio_thread;
|
||||
|
||||
|
@ -666,10 +661,10 @@ int commander_thread_main(int argc, char *argv[])
|
|||
// We want to accept RC inputs as default
|
||||
status.rc_input_blocked = false;
|
||||
status.main_state = MAIN_STATE_MANUAL;
|
||||
status.set_nav_state = NAVIGATION_STATE_MANUAL;
|
||||
status.nav_state = NAVIGATION_STATE_MANUAL;
|
||||
status.arming_state = ARMING_STATE_INIT;
|
||||
status.hil_state = HIL_STATE_OFF;
|
||||
status.failsafe_state = FAILSAFE_STATE_NORMAL;
|
||||
status.failsafe = false;
|
||||
|
||||
/* neither manual nor offboard control commands have been received */
|
||||
status.offboard_control_signal_found_once = false;
|
||||
|
@ -678,6 +673,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* mark all signals lost as long as they haven't been found */
|
||||
status.rc_signal_lost = true;
|
||||
status.offboard_control_signal_lost = true;
|
||||
status.data_link_lost = true;
|
||||
|
||||
/* set battery warning flag */
|
||||
status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
|
||||
|
@ -771,6 +767,11 @@ int commander_thread_main(int argc, char *argv[])
|
|||
struct offboard_control_setpoint_s sp_offboard;
|
||||
memset(&sp_offboard, 0, sizeof(sp_offboard));
|
||||
|
||||
/* Subscribe to telemetry status */
|
||||
int telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
|
||||
struct telemetry_status_s telemetry;
|
||||
memset(&telemetry, 0, sizeof(telemetry));
|
||||
|
||||
/* Subscribe to global position */
|
||||
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
struct vehicle_global_position_s global_position;
|
||||
|
@ -908,6 +909,12 @@ int commander_thread_main(int argc, char *argv[])
|
|||
orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
|
||||
}
|
||||
|
||||
orb_check(telemetry_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
orb_copy(ORB_ID(telemetry_status), telemetry_sub, &telemetry);
|
||||
}
|
||||
|
||||
orb_check(sensor_sub, &updated);
|
||||
|
||||
if (updated) {
|
||||
|
@ -1186,7 +1193,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
|
||||
}
|
||||
|
||||
/* start RC input check */
|
||||
/* RC input check */
|
||||
if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
|
||||
/* handle the case where RC signal was regained */
|
||||
if (!status.rc_signal_found_once) {
|
||||
|
@ -1198,9 +1205,6 @@ int commander_thread_main(int argc, char *argv[])
|
|||
if (status.rc_signal_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "#audio: RC signal regained");
|
||||
status_changed = true;
|
||||
|
||||
status.failsafe_state = FAILSAFE_STATE_NORMAL;
|
||||
failsafe_state_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1271,12 +1275,6 @@ int commander_thread_main(int argc, char *argv[])
|
|||
mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied");
|
||||
}
|
||||
|
||||
|
||||
// if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
|
||||
// /* recover from failsafe */
|
||||
// (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
|
||||
// }
|
||||
|
||||
/* evaluate the main state machine according to mode switches */
|
||||
transition_result_t main_res = set_main_state_rc(&status, &sp_man);
|
||||
|
||||
|
@ -1295,34 +1293,24 @@ int commander_thread_main(int argc, char *argv[])
|
|||
mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST");
|
||||
status.rc_signal_lost = true;
|
||||
status_changed = true;
|
||||
|
||||
if (!(status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION && !mission_result.mission_finished)) {
|
||||
|
||||
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
||||
if (status.condition_global_position_valid) {
|
||||
status.failsafe_state = FAILSAFE_STATE_RC_LOSS;
|
||||
} else {
|
||||
status.failsafe_state = FAILSAFE_STATE_LAND;
|
||||
}
|
||||
failsafe_state_changed = true;
|
||||
} else {
|
||||
mavlink_log_info(mavlink_fd, "#audio: no RTL during Mission");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* hack to detect if we finished a mission after we lost RC, so that we can trigger RTL now */
|
||||
if (status.rc_signal_lost && status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION &&
|
||||
mission_result.mission_finished && status.failsafe_state != FAILSAFE_STATE_RC_LOSS) {
|
||||
/* if we have a global position, we can switch to RTL, if not, we can try to land */
|
||||
if (status.condition_global_position_valid) {
|
||||
status.failsafe_state = FAILSAFE_STATE_RC_LOSS;
|
||||
mavlink_log_info(mavlink_fd, "#audio: RTL after Mission is finished");
|
||||
} else {
|
||||
/* this probably doesn't make sense since we are in mission and have global position */
|
||||
status.failsafe_state = FAILSAFE_STATE_LAND;
|
||||
/* data link check */
|
||||
if (hrt_abstime() < telemetry.heartbeat_time + DL_TIMEOUT) {
|
||||
/* handle the case where RC signal was regained */
|
||||
if (status.data_link_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "#audio: data link regained");
|
||||
status.data_link_lost = false;
|
||||
status_changed = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (!status.data_link_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: DATA LINK LOST");
|
||||
status.data_link_lost = false;
|
||||
status_changed = true;
|
||||
}
|
||||
failsafe_state_changed = true;
|
||||
}
|
||||
|
||||
/* handle commands last, as the system needs to be updated to handle them */
|
||||
|
@ -1377,7 +1365,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
was_armed = armed.armed;
|
||||
|
||||
/* now set nav state according to failsafe and main state */
|
||||
/* now set navigation state according to failsafe and main state */
|
||||
set_nav_state(&status);
|
||||
|
||||
if (main_state_changed) {
|
||||
|
@ -1388,7 +1376,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
|
||||
if (failsafe_state_changed) {
|
||||
status_changed = true;
|
||||
mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %s", failsafe_states_str[status.failsafe_state]);
|
||||
mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %i", status.failsafe);
|
||||
failsafe_state_changed = false;
|
||||
}
|
||||
|
||||
|
@ -1415,7 +1403,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* play tune on battery critical */
|
||||
set_tune(TONE_BATTERY_WARNING_FAST_TUNE);
|
||||
|
||||
} else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe_state != FAILSAFE_STATE_NORMAL) {
|
||||
} else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe) {
|
||||
/* play tune on battery warning or failsafe */
|
||||
set_tune(TONE_BATTERY_WARNING_SLOW_TUNE);
|
||||
|
||||
|
@ -1519,7 +1507,7 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
|
|||
|
||||
if (set_normal_color) {
|
||||
/* set color */
|
||||
if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status->failsafe_state != FAILSAFE_STATE_NORMAL) {
|
||||
if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status->failsafe) {
|
||||
rgbled_set_color(RGBLED_COLOR_AMBER);
|
||||
/* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
|
||||
|
||||
|
@ -1667,7 +1655,7 @@ set_control_mode()
|
|||
control_mode.flag_external_manual_override_ok = !status.is_rotary_wing;
|
||||
control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON;
|
||||
|
||||
switch (status.set_nav_state) {
|
||||
switch (status.nav_state) {
|
||||
case NAVIGATION_STATE_MANUAL:
|
||||
control_mode.flag_control_manual_enabled = true;
|
||||
control_mode.flag_control_auto_enabled = false;
|
||||
|
@ -1719,8 +1707,6 @@ set_control_mode()
|
|||
case NAVIGATION_STATE_AUTO_MISSION:
|
||||
case NAVIGATION_STATE_AUTO_LOITER:
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||
control_mode.flag_control_manual_enabled = false;
|
||||
control_mode.flag_control_auto_enabled = true;
|
||||
control_mode.flag_control_rates_enabled = true;
|
||||
|
|
|
@ -354,7 +354,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub,
|
|||
}
|
||||
}
|
||||
|
||||
if (ret = TRANSITION_CHANGED) {
|
||||
if (ret == TRANSITION_CHANGED) {
|
||||
current_status->hil_state = new_state;
|
||||
current_status->timestamp = hrt_absolute_time();
|
||||
// XXX also set lockdown here
|
||||
|
@ -363,67 +363,95 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub,
|
|||
return ret;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Check failsafe and main status and set navigation status for navigator accordingly
|
||||
*/
|
||||
void set_nav_state(struct vehicle_status_s *status)
|
||||
{
|
||||
switch (status->failsafe_state) {
|
||||
case FAILSAFE_STATE_NORMAL:
|
||||
/* evaluate main state to decide in normal (non-failsafe) mode */
|
||||
switch (status->main_state) {
|
||||
case MAIN_STATE_MANUAL:
|
||||
status->set_nav_state = NAVIGATION_STATE_MANUAL;
|
||||
break;
|
||||
status->failsafe = false;
|
||||
|
||||
case MAIN_STATE_ALTCTL:
|
||||
status->set_nav_state = NAVIGATION_STATE_ALTCTL;
|
||||
break;
|
||||
/* evaluate main state to decide in normal (non-failsafe) mode */
|
||||
switch (status->main_state) {
|
||||
case MAIN_STATE_ACRO:
|
||||
case MAIN_STATE_MANUAL:
|
||||
case MAIN_STATE_ALTCTL:
|
||||
case MAIN_STATE_POSCTL:
|
||||
/* require RC for all manual modes */
|
||||
if (status->rc_signal_lost) {
|
||||
status->failsafe = true;
|
||||
|
||||
case MAIN_STATE_POSCTL:
|
||||
status->set_nav_state = NAVIGATION_STATE_POSCTL;
|
||||
break;
|
||||
} else {
|
||||
switch (status->main_state) {
|
||||
case MAIN_STATE_ACRO:
|
||||
status->nav_state = NAVIGATION_STATE_ACRO;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_AUTO_MISSION:
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
break;
|
||||
case MAIN_STATE_MANUAL:
|
||||
status->nav_state = NAVIGATION_STATE_MANUAL;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_AUTO_LOITER:
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_LOITER;
|
||||
break;
|
||||
case MAIN_STATE_ALTCTL:
|
||||
status->nav_state = NAVIGATION_STATE_ALTCTL;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_AUTO_RTL:
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
break;
|
||||
case MAIN_STATE_POSCTL:
|
||||
status->nav_state = NAVIGATION_STATE_POSCTL;
|
||||
break;
|
||||
|
||||
case MAIN_STATE_ACRO:
|
||||
status->set_nav_state = NAVIGATION_STATE_ACRO;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
default:
|
||||
status->nav_state = NAVIGATION_STATE_MANUAL;
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case FAILSAFE_STATE_RC_LOSS:
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS;
|
||||
case MAIN_STATE_AUTO_MISSION:
|
||||
/* require data link and global position */
|
||||
if (status->data_link_lost || !status->condition_global_position_valid) {
|
||||
status->failsafe = true;
|
||||
|
||||
} else {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
|
||||
}
|
||||
break;
|
||||
|
||||
case FAILSAFE_STATE_DL_LOSS:
|
||||
status->set_nav_state = NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS;
|
||||
case MAIN_STATE_AUTO_LOITER:
|
||||
/* require data link and local position */
|
||||
if (status->data_link_lost || !status->condition_local_position_valid) {
|
||||
status->failsafe = true;
|
||||
|
||||
} else {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
|
||||
}
|
||||
break;
|
||||
|
||||
case FAILSAFE_STATE_LAND:
|
||||
status->set_nav_state = NAVIGATION_STATE_LAND;
|
||||
break;
|
||||
case MAIN_STATE_AUTO_RTL:
|
||||
/* require global position and home */
|
||||
if (!status->condition_global_position_valid || !status->condition_home_position_valid) {
|
||||
status->failsafe = true;
|
||||
|
||||
case FAILSAFE_STATE_TERMINATION:
|
||||
status->set_nav_state = NAVIGATION_STATE_TERMINATION;
|
||||
} else {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (status->failsafe) {
|
||||
if (status->condition_global_position_valid && status->condition_home_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_AUTO_RTL;
|
||||
|
||||
} else if (status->condition_local_position_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_LAND;
|
||||
|
||||
} else if (status->condition_local_altitude_valid) {
|
||||
status->nav_state = NAVIGATION_STATE_DESCEND;
|
||||
|
||||
} else {
|
||||
status->nav_state = NAVIGATION_STATE_TERMINATION;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -63,8 +63,6 @@ transition_result_t arming_state_transition(struct vehicle_status_s *current_sta
|
|||
|
||||
transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
|
||||
|
||||
transition_result_t failsafe_state_transition(struct vehicle_status_s *status, failsafe_state_t new_failsafe_state);
|
||||
|
||||
transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
|
||||
|
||||
void set_nav_state(struct vehicle_status_s *status);
|
||||
|
|
|
@ -264,7 +264,7 @@ void gpio_led_cycle(FAR void *arg)
|
|||
pattern = 0x2A; // *_*_*_ fast blink (armed, error)
|
||||
|
||||
} else if (priv->status.arming_state == ARMING_STATE_ARMED) {
|
||||
if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE && priv->status.failsafe_state == FAILSAFE_STATE_NORMAL) {
|
||||
if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE && !priv->status.failsafe) {
|
||||
pattern = 0x3f; // ****** solid (armed)
|
||||
|
||||
} else {
|
||||
|
|
|
@ -118,7 +118,7 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
|
|||
union px4_custom_mode custom_mode;
|
||||
custom_mode.data = 0;
|
||||
|
||||
switch (status->set_nav_state) {
|
||||
switch (status->nav_state) {
|
||||
|
||||
case NAVIGATION_STATE_MANUAL:
|
||||
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
|
||||
|
@ -161,8 +161,6 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
|
|||
break;
|
||||
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
|
||||
| MAV_MODE_FLAG_STABILIZE_ENABLED
|
||||
| MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||
|
|
|
@ -112,6 +112,7 @@ private:
|
|||
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
|
||||
void handle_message_radio_status(mavlink_message_t *msg);
|
||||
void handle_message_manual_control(mavlink_message_t *msg);
|
||||
void handle_message_heartbeat(mavlink_message_t *msg);
|
||||
void handle_message_hil_sensor(mavlink_message_t *msg);
|
||||
void handle_message_hil_gps(mavlink_message_t *msg);
|
||||
void handle_message_hil_state_quaternion(mavlink_message_t *msg);
|
||||
|
@ -138,6 +139,7 @@ private:
|
|||
orb_advert_t _telemetry_status_pub;
|
||||
orb_advert_t _rc_pub;
|
||||
orb_advert_t _manual_pub;
|
||||
hrt_abstime _telemetry_heartbeat_time;
|
||||
int _hil_frames;
|
||||
uint64_t _old_timestamp;
|
||||
bool _hil_local_proj_inited;
|
||||
|
|
|
@ -336,7 +336,7 @@ Navigator::task_main()
|
|||
}
|
||||
|
||||
/* Do stuff according to navigation state set by commander */
|
||||
switch (_vstatus.set_nav_state) {
|
||||
switch (_vstatus.nav_state) {
|
||||
case NAVIGATION_STATE_MANUAL:
|
||||
case NAVIGATION_STATE_ACRO:
|
||||
case NAVIGATION_STATE_ALTCTL:
|
||||
|
@ -351,8 +351,6 @@ Navigator::task_main()
|
|||
_navigation_mode = &_loiter;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS:
|
||||
case NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS:
|
||||
_navigation_mode = &_rtl;
|
||||
break;
|
||||
case NAVIGATION_STATE_LAND:
|
||||
|
|
|
@ -1117,7 +1117,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
log_msg.msg_type = LOG_STAT_MSG;
|
||||
log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
|
||||
log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
|
||||
log_msg.body.log_STAT.failsafe_state = (uint8_t) buf_status.failsafe_state;
|
||||
log_msg.body.log_STAT.failsafe_state = (uint8_t) buf_status.failsafe;
|
||||
log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
|
||||
log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
|
||||
log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
|
||||
|
|
|
@ -59,7 +59,9 @@
|
|||
* @addtogroup topics @{
|
||||
*/
|
||||
|
||||
/* main state machine */
|
||||
/**
|
||||
* Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
|
||||
*/
|
||||
typedef enum {
|
||||
MAIN_STATE_MANUAL = 0,
|
||||
MAIN_STATE_ALTCTL,
|
||||
|
@ -89,15 +91,9 @@ typedef enum {
|
|||
HIL_STATE_ON
|
||||
} hil_state_t;
|
||||
|
||||
typedef enum {
|
||||
FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
|
||||
FAILSAFE_STATE_RC_LOSS, /**< Return To Launch on remote control loss */
|
||||
FAILSAFE_STATE_DL_LOSS, /**< Return To Launch on datalink loss */
|
||||
FAILSAFE_STATE_LAND, /**< Land as safe as possible */
|
||||
FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
|
||||
FAILSAFE_STATE_MAX,
|
||||
} failsafe_state_t;
|
||||
|
||||
/**
|
||||
* Navigation state, i.e. "what should vehicle do".
|
||||
*/
|
||||
typedef enum {
|
||||
NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
|
||||
NAVIGATION_STATE_ACRO, /**< Acro mode */
|
||||
|
@ -106,9 +102,8 @@ typedef enum {
|
|||
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
|
||||
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
|
||||
NAVIGATION_STATE_AUTO_RTL, /**< Auto RTL mode */
|
||||
NAVIGATION_STATE_AUTO_FAILSAFE_RC_LOSS, /**< Auto failsafe on RC loss mode */
|
||||
NAVIGATION_STATE_AUTO_FAILSAFE_DL_LOSS, /**< Auto failsafe on datalink loss mode */
|
||||
NAVIGATION_STATE_LAND, /**< Land mode */
|
||||
NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
|
||||
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
|
||||
} navigation_state_t;
|
||||
|
||||
|
@ -171,10 +166,10 @@ struct vehicle_status_s {
|
|||
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
|
||||
|
||||
main_state_t main_state; /**< main state machine */
|
||||
navigation_state_t set_nav_state; /**< set navigation state machine to specified value */
|
||||
navigation_state_t nav_state; /**< set navigation state machine to specified value */
|
||||
arming_state_t arming_state; /**< current arming state */
|
||||
hil_state_t hil_state; /**< current hil state */
|
||||
failsafe_state_t failsafe_state; /**< current failsafe state */
|
||||
bool failsafe; /**< true if system is in failsafe state */
|
||||
|
||||
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
|
||||
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
|
||||
|
@ -199,6 +194,8 @@ struct vehicle_status_s {
|
|||
bool rc_signal_lost; /**< true if RC reception lost */
|
||||
bool rc_input_blocked; /**< set if RC input should be ignored */
|
||||
|
||||
bool data_link_lost; /**< datalink to GCS lost */
|
||||
|
||||
bool offboard_control_signal_found_once;
|
||||
bool offboard_control_signal_lost;
|
||||
bool offboard_control_signal_weak;
|
||||
|
|
Loading…
Reference in New Issue