PX4 Firmware
PX4 Autopilot Software http://px4.io
|
State machine helper functions implementations. More...
#include <px4_platform_common/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 "Arming/PreFlightCheck/PreFlightCheck.hpp"
#include "state_machine_helper.h"
#include "commander_helper.h"
Go to the source code of this file.
Variables | |
static constexpr const char | reason_no_rc [] = "no RC" |
static constexpr const char | reason_no_offboard [] = "no offboard" |
static constexpr const char | reason_no_rc_and_no_offboard [] = "no RC and no offboard" |
static constexpr const char | reason_no_local_position [] = "no local position" |
static constexpr const char | reason_no_global_position [] = "no global position" |
static constexpr const char | reason_no_datalink [] = "no datalink" |
static constexpr const bool | arming_transitions [vehicle_status_s::ARMING_STATE_MAX][vehicle_status_s::ARMING_STATE_MAX] |
const char *const | arming_state_names [vehicle_status_s::ARMING_STATE_MAX] |
static hrt_abstime | last_preflight_check = 0 |
initialize so it gets checked immediately More... | |
State machine helper functions implementations.
Definition in file state_machine_helper.cpp.
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 | ||
) |
Definition at line 106 of file state_machine_helper.cpp.
References PreFlightCheck::ARM_REQ_GPS_BIT, actuator_armed_s::armed, actuator_armed_s::armed_time_ms, vehicle_status_s::arming_state, arming_state_names, arming_transitions, vehicle_status_flags_s::condition_system_sensors_initialized, vehicle_status_s::hil_state, hrt_absolute_time(), hrt_elapsed_time(), last_preflight_check, actuator_armed_s::lockdown, mavlink_log_critical, PreFlightCheck::preArmCheck(), PreFlightCheck::preflightCheck(), actuator_armed_s::ready_to_arm, TRANSITION_CHANGED, TRANSITION_DENIED, and TRANSITION_NOT_CHANGED.
Referenced by arm_disarm(), StateMachineHelperTest::armingStateTransitionTest(), commander_low_prio_loop(), Commander::run(), and shutdown_if_allowed().
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 | ||
) |
Definition at line 1014 of file state_machine_helper.cpp.
References vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_home_position_valid, hrt_absolute_time(), LAND, commander_state_s::main_state, mavlink_log_critical, mavlink_log_emergency, RETURN, RETURN_OR_LAND, commander_state_s::timestamp, and WARNING.
Referenced by Commander::battery_status_check().
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 | ||
) |
Definition at line 724 of file state_machine_helper.cpp.
References vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_local_altitude_valid, vehicle_status_flags_s::condition_local_position_valid, vehicle_status_flags_s::condition_local_velocity_valid, enable_failsafe(), vehicle_status_s::nav_state, reason_no_global_position, reason_no_local_position, and vehicle_status_s::vehicle_type.
Referenced by set_nav_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.
Definition at line 391 of file state_machine_helper.cpp.
References vehicle_status_s::arming_state, vehicle_status_s::failsafe, and mavlink_log_critical.
Referenced by check_invalid_pos_nav_state(), and set_nav_state().
bool is_safe | ( | const safety_s & | safety, |
const actuator_armed_s & | armed | ||
) |
Definition at line 248 of file state_machine_helper.cpp.
References actuator_armed_s::armed, actuator_armed_s::lockdown, actuator_armed_s::manual_lockdown, safety_s::safety_off, and safety_s::safety_switch_available.
Referenced by commander_low_prio_loop(), and StateMachineHelperTest::isSafeTest().
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 | ||
) |
Definition at line 260 of file state_machine_helper.cpp.
References vehicle_status_flags_s::condition_auto_mission_available, vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_home_position_valid, vehicle_status_flags_s::condition_local_altitude_valid, vehicle_status_flags_s::condition_local_position_valid, hrt_absolute_time(), commander_state_s::main_state, vehicle_status_flags_s::offboard_control_signal_lost, commander_state_s::timestamp, TRANSITION_CHANGED, TRANSITION_DENIED, TRANSITION_NOT_CHANGED, and vehicle_status_s::vehicle_type.
Referenced by commander_main(), Commander::handle_command(), StateMachineHelperTest::mainStateTransitionTest(), Commander::run(), set_link_loss_nav_state(), Commander::set_main_state_override_on(), and Commander::set_main_state_rc().
void reset_link_loss_globals | ( | actuator_armed_s * | armed, |
const bool | old_failsafe, | ||
const link_loss_actions_t | link_loss_act | ||
) |
Definition at line 852 of file state_machine_helper.cpp.
References actuator_armed_s::force_failsafe, actuator_armed_s::lockdown, LOCKDOWN, and TERMINATE.
Referenced by set_nav_state().
void reset_offboard_loss_globals | ( | actuator_armed_s * | armed, |
const bool | old_failsafe, | ||
const offboard_loss_actions_t | offboard_loss_act, | ||
const offboard_loss_rc_actions_t | offboard_loss_rc_act | ||
) |
Definition at line 993 of file state_machine_helper.cpp.
References actuator_armed_s::force_failsafe, actuator_armed_s::lockdown, LOCKDOWN, and TERMINATE.
Referenced by set_nav_state().
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 | ||
) |
Definition at line 784 of file state_machine_helper.cpp.
References AUTO_LAND, AUTO_LOITER, AUTO_RECOVER, AUTO_RTL, vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_home_position_valid, vehicle_status_flags_s::condition_local_altitude_valid, vehicle_status_flags_s::condition_local_position_valid, DISABLED, actuator_armed_s::force_failsafe, actuator_armed_s::lockdown, LOCKDOWN, main_state_transition(), vehicle_status_s::nav_state, TERMINATE, and vehicle_status_s::vehicle_type.
Referenced by set_nav_state().
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.
Definition at line 403 of file state_machine_helper.cpp.
References vehicle_status_s::arming_state, check_invalid_pos_nav_state(), vehicle_status_s::data_link_lost, DISABLED, enable_failsafe(), vehicle_status_s::engine_failure, vehicle_status_s::failsafe, LAND_TERMINATE, commander_state_s::main_state, vehicle_status_s::mission_failure, vehicle_status_s::nav_state, vehicle_status_flags_s::offboard_control_loss_timeout, vehicle_status_flags_s::offboard_control_signal_lost, vehicle_status_s::rc_signal_lost, reason_no_datalink, reason_no_offboard, reason_no_rc, reason_no_rc_and_no_offboard, reset_link_loss_globals(), reset_offboard_loss_globals(), set_link_loss_nav_state(), set_offboard_loss_nav_state(), set_offboard_loss_rc_nav_state(), vehicle_status_s::vehicle_type, VEHICLE_TYPE_FIXED_WING, and vehicle_status_flags_s::vtol_transition_failure.
Referenced by Commander::run().
void set_offboard_loss_nav_state | ( | vehicle_status_s * | status, |
actuator_armed_s * | armed, | ||
const vehicle_status_flags_s & | status_flags, | ||
const offboard_loss_actions_t | offboard_loss_act | ||
) |
Definition at line 864 of file state_machine_helper.cpp.
References AUTO_LAND, AUTO_LOITER, AUTO_RTL, vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_home_position_valid, vehicle_status_flags_s::condition_local_altitude_valid, DISABLED, actuator_armed_s::force_failsafe, actuator_armed_s::lockdown, LOCKDOWN, vehicle_status_s::nav_state, TERMINATE, and vehicle_status_s::vehicle_type.
Referenced by set_nav_state().
void set_offboard_loss_rc_nav_state | ( | vehicle_status_s * | status, |
actuator_armed_s * | armed, | ||
const vehicle_status_flags_s & | status_flags, | ||
const offboard_loss_rc_actions_t | offboard_loss_rc_act | ||
) |
Definition at line 919 of file state_machine_helper.cpp.
References AUTO_LAND, AUTO_LOITER, AUTO_RTL, vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::condition_home_position_valid, vehicle_status_flags_s::condition_local_altitude_valid, DISABLED, actuator_armed_s::force_failsafe, actuator_armed_s::lockdown, LOCKDOWN, MANUAL_ALTITUDE, MANUAL_ATTITUDE, MANUAL_POSITION, vehicle_status_s::nav_state, TERMINATE, and vehicle_status_s::vehicle_type.
Referenced by set_nav_state().
const char* const arming_state_names[vehicle_status_s::ARMING_STATE_MAX] |
Definition at line 77 of file state_machine_helper.cpp.
Referenced by arming_state_transition(), and print_status().
|
static |
Definition at line 66 of file state_machine_helper.cpp.
Referenced by arming_state_transition().
|
static |
initialize so it gets checked immediately
Definition at line 86 of file state_machine_helper.cpp.
Referenced by arming_state_transition().
|
static |
Definition at line 58 of file state_machine_helper.cpp.
Referenced by set_nav_state().
|
static |
Definition at line 57 of file state_machine_helper.cpp.
Referenced by check_invalid_pos_nav_state().
|
static |
Definition at line 56 of file state_machine_helper.cpp.
Referenced by check_invalid_pos_nav_state().
|
static |
Definition at line 54 of file state_machine_helper.cpp.
Referenced by set_nav_state().
|
static |
Definition at line 53 of file state_machine_helper.cpp.
Referenced by set_nav_state().
|
static |
Definition at line 55 of file state_machine_helper.cpp.
Referenced by set_nav_state().