PX4 Firmware
PX4 Autopilot Software http://px4.io
state_machine_helper.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file state_machine_helper.h
36  * State machine helper functions definitions
37  *
38  * @author Thomas Gubler <thomasgubler@student.ethz.ch>
39  * @author Julian Oes <julian@oes.ch>
40  */
41 
42 #ifndef STATE_MACHINE_HELPER_H_
43 #define STATE_MACHINE_HELPER_H_
44 
45 #include <drivers/drv_hrt.h>
46 
47 #include <uORB/uORB.h>
51 #include <uORB/topics/safety.h>
54 
55 typedef enum {
60 
61 enum class link_loss_actions_t {
62  DISABLED = 0,
63  AUTO_LOITER = 1, // Hold mode
64  AUTO_RTL = 2, // Return mode
65  AUTO_LAND = 3, // Land mode
66  AUTO_RECOVER = 4, // Data Link Auto Recovery (CASA Outback Challenge rules)
67  TERMINATE = 5, // Terminate flight (set actuator outputs to failsafe values, and stop controllers)
68  LOCKDOWN = 6, // Lock actuators (set actuator outputs to disarmed values)
69 };
70 
72  DISABLED = -1,
73  AUTO_LAND = 0, // Land mode
74  AUTO_LOITER = 1, // Hold mode
75  AUTO_RTL = 2, // Return mode
76  TERMINATE = 3, // Terminate flight (set actuator outputs to failsafe values, and stop controllers)
77  LOCKDOWN = 4, // Lock actuators (set actuator outputs to disarmed values)
78 };
79 
81  DISABLED = -1, // Disabled
82  MANUAL_POSITION = 0, // Position mode
83  MANUAL_ALTITUDE = 1, // Altitude mode
84  MANUAL_ATTITUDE = 2, // Manual
85  AUTO_RTL = 3, // Return mode
86  AUTO_LAND = 4, // Land mode
87  AUTO_LOITER = 5, // Hold mode
88  TERMINATE = 6, // Terminate flight (set actuator outputs to failsafe values, and stop controllers)
89  LOCKDOWN = 7, // Lock actuators (set actuator outputs to disarmed values)
90 };
91 
93  ALTITUDE_MANUAL = 0, // Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL.
94  LAND_TERMINATE = 1, // Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION.
95 };
96 
97 extern const char *const arming_state_names[];
98 
99 bool is_safe(const safety_s &safety, const actuator_armed_s &armed);
100 
102 arming_state_transition(vehicle_status_s *status, const safety_s &safety, const arming_state_t new_arming_state,
103  actuator_armed_s *armed, const bool fRunPreArmChecks, orb_advert_t *mavlink_log_pub,
104  vehicle_status_flags_s *status_flags, const uint8_t arm_requirements, const hrt_abstime &time_since_boot);
105 
107 main_state_transition(const vehicle_status_s &status, const main_state_t new_main_state,
109 
110 void enable_failsafe(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub, const char *reason);
111 
112 bool set_nav_state(vehicle_status_s *status, actuator_armed_s *armed, commander_state_s *internal_state,
113  orb_advert_t *mavlink_log_pub, const link_loss_actions_t data_link_loss_act, const bool mission_finished,
114  const bool stay_in_failsafe, const vehicle_status_flags_s &status_flags, bool landed,
115  const link_loss_actions_t rc_loss_act, const offboard_loss_actions_t offb_loss_act,
116  const offboard_loss_rc_actions_t offb_loss_rc_act,
117  const position_nav_loss_actions_t posctl_nav_loss_act);
118 
119 /*
120  * Checks the validty of position data against the requirements of the current navigation
121  * mode and switches mode if position data required is not available.
122  */
124  const vehicle_status_flags_s &status_flags, const bool use_rc, const bool using_global_pos);
125 
126 
127 // COM_LOW_BAT_ACT parameter values
128 typedef enum LOW_BAT_ACTION {
129  WARNING = 0, // Warning
130  RETURN = 1, // Return mode
131  LAND = 2, // Land mode
132  RETURN_OR_LAND = 3 // Return mode at critically low level, Land mode at current position if reaching dangerously low levels
134 
136  const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const uint8_t battery_warning,
137  const low_battery_action_t low_bat_action);
138 
139 #endif /* STATE_MACHINE_HELPER_H_ */
static orb_advert_t * mavlink_log_pub
static struct vehicle_status_s status
Definition: Commander.cpp:138
API for the uORB lightweight object broker.
static struct vehicle_status_flags_s status_flags
Definition: Commander.cpp:155
static struct commander_state_s internal_state
Definition: Commander.cpp:142
link_loss_actions_t
uint8_t arming_state_t
Definition: uORB.h:257
High-resolution timer with callouts and timekeeping.
static struct safety_s safety
Definition: Commander.cpp:140
offboard_loss_actions_t
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
Definition: Commander.cpp:139
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.
Definition: drv_hrt.h:58
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
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)
uint8_t main_state_t
Definition: uORB.h:258
static uint8_t arm_requirements
Definition: Commander.cpp:159
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
transition_result_t
bool is_safe(const safety_s &safety, const actuator_armed_s &armed)
const char *const arming_state_names[]