42 #ifndef STATE_MACHINE_HELPER_H_ 43 #define STATE_MACHINE_HELPER_H_
static orb_advert_t * mavlink_log_pub
static struct vehicle_status_s status
API for the uORB lightweight object broker.
static struct vehicle_status_flags_s status_flags
static struct commander_state_s internal_state
High-resolution timer with callouts and timekeeping.
static struct safety_s safety
bool set_nav_state(vehicle_status_s *status, actuator_armed_s *armed, commander_state_s *internal_state, orb_advert_t *mavlink_log_pub, const link_loss_actions_t data_link_loss_act, const bool mission_finished, const bool stay_in_failsafe, const vehicle_status_flags_s &status_flags, bool landed, const link_loss_actions_t rc_loss_act, const offboard_loss_actions_t offb_loss_act, const offboard_loss_rc_actions_t offb_loss_rc_act, const position_nav_loss_actions_t posctl_nav_loss_act)
Check failsafe and main status and set navigation status for navigator accordingly.
static struct actuator_armed_s armed
enum LOW_BAT_ACTION low_battery_action_t
bool check_invalid_pos_nav_state(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &status_flags, const bool use_rc, const bool using_global_pos)
void enable_failsafe(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub, const char *reason)
Enable failsafe and report to user.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
transition_result_t arming_state_transition(vehicle_status_s *status, const safety_s &safety, const arming_state_t new_arming_state, actuator_armed_s *armed, const bool fRunPreArmChecks, orb_advert_t *mavlink_log_pub, vehicle_status_flags_s *status_flags, const uint8_t arm_requirements, const hrt_abstime &time_since_boot)
static uint8_t arm_requirements
transition_result_t main_state_transition(const vehicle_status_s &status, const main_state_t new_main_state, const vehicle_status_flags_s &status_flags, commander_state_s *internal_state)
offboard_loss_rc_actions_t
void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const uint8_t battery_warning, const low_battery_action_t low_bat_action)
position_nav_loss_actions_t
bool is_safe(const safety_s &safety, const actuator_armed_s &armed)
const char *const arming_state_names[]