Firmware
Typedefs | Enumerations | Functions | Variables
state_machine_helper.h File Reference

State machine helper functions definitions. More...

#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/safety.h>
#include <uORB/topics/commander_state.h>
#include <uORB/topics/vehicle_status_flags.h>

Go to the source code of this file.

Typedefs

typedef enum LOW_BAT_ACTION low_battery_action_t
 

Enumerations

enum  transition_result_t { TRANSITION_DENIED = -1, TRANSITION_NOT_CHANGED = 0, TRANSITION_CHANGED }
 
enum  link_loss_actions_t {
  DISABLED = 0, AUTO_LOITER = 1, AUTO_RTL = 2, AUTO_LAND = 3,
  AUTO_RECOVER = 4, TERMINATE = 5, LOCKDOWN = 6
}
 
enum  arm_requirements_t { ARM_REQ_NONE = 0, ARM_REQ_MISSION_BIT = (1 << 0), ARM_REQ_ARM_AUTH_BIT = (1 << 1), ARM_REQ_GPS_BIT = (1 << 2) }
 
enum  LOW_BAT_ACTION { WARNING = 0, RETURN = 1, LAND = 2, RETURN_OR_LAND = 3 }
 

Functions

bool is_safe (const safety_s &safety, const actuator_armed_s &armed)
 
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)
 
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)
 
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.
 
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 int offb_loss_act, const int offb_loss_rc_act, const int posctl_nav_loss_act)
 Check failsafe and main status and set navigation status for navigator accordingly.
 
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)
 
bool prearm_check (orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &status_flags, const safety_s &safety, const uint8_t arm_requirements)
 
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)
 

Variables

const char *const arming_state_names []
 

Detailed Description

State machine helper functions definitions.

Author
Thomas Gubler thoma.nosp@m.sgub.nosp@m.ler@s.nosp@m.tude.nosp@m.nt.et.nosp@m.hz.c.nosp@m.h
Julian Oes julia.nosp@m.n@oe.nosp@m.s.ch