Firmware
Functions | Variables
state_machine_helper.cpp File Reference

State machine helper functions implementations. More...

#include <px4_config.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_status.h>
#include <systemlib/mavlink_log.h>
#include <drivers/drv_hrt.h>
#include "state_machine_helper.h"
#include "commander_helper.h"
#include "PreflightCheck.h"
#include "arm_auth.h"

Functions

void set_link_loss_nav_state (vehicle_status_s *status, actuator_armed_s *armed, const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const link_loss_actions_t link_loss_act, uint8_t auto_recovery_nav_state)
 
void reset_link_loss_globals (actuator_armed_s *armed, const bool old_failsafe, const link_loss_actions_t link_loss_act)
 
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)
 
bool is_safe (const safety_s &safety, const actuator_armed_s &armed)
 
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_battery_action)
 

Variables

const char *const arming_state_names [vehicle_status_s::ARMING_STATE_MAX]
 

Detailed Description

State machine helper functions implementations.

Author
Thomas Gubler thoma.nosp@m.s@px.nosp@m.4.io
Julian Oes julia.nosp@m.n@oe.nosp@m.s.ch
Sander Smeets sande.nosp@m.r@dr.nosp@m.onesl.nosp@m.ab.c.nosp@m.om

Variable Documentation

§ arming_state_names

const char* const arming_state_names[vehicle_status_s::ARMING_STATE_MAX]
Initial value:
= {
"INIT",
"STANDBY",
"ARMED",
"STANDBY_ERROR",
"REBOOT",
"IN_AIR_RESTORE",
}