CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/defines.h
Views: 1798
1
#pragma once
2
3
// Internal defines, don't edit and expect things to work
4
// -------------------------------------------------------
5
6
#define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an
7
// arbitrary representation of servo max travel.
8
9
#define MIN_AIRSPEED_MIN 5 // m/s, used for arming check and speed scaling
10
11
#define TAKEOFF_RUDDER_WARNING_TIMEOUT 3000 //ms that GCS warning about not returning arming rudder to neutral repeats
12
13
#define GPS_GND_CRS_MIN_SPD 5 // m/s, used to set when intial_direction.heading is captured in NAV_TAKEOFF and Mode TAKEOFF
14
15
// failsafe
16
// ----------------------
17
enum failsafe_state {
18
FAILSAFE_NONE=0,
19
FAILSAFE_SHORT=1,
20
FAILSAFE_LONG=2,
21
FAILSAFE_GCS=3
22
};
23
24
25
// GCS failsafe types for FS_GCS_ENABL parameter
26
enum gcs_failsafe {
27
GCS_FAILSAFE_OFF = 0, // no GCS failsafe
28
GCS_FAILSAFE_HEARTBEAT = 1, // failsafe if we stop receiving heartbeat
29
GCS_FAILSAFE_HB_RSSI = 2, // failsafe if we stop receiving
30
// heartbeat or if RADIO.remrssi
31
// drops to 0
32
GCS_FAILSAFE_HB_AUTO = 3 // failsafe if we stop receiving heartbeat
33
// while in AUTO mode
34
};
35
36
enum failsafe_action_short {
37
FS_ACTION_SHORT_BESTGUESS = 0, // CIRCLE/no change(if already in AUTO|GUIDED|LOITER)
38
FS_ACTION_SHORT_CIRCLE = 1,
39
FS_ACTION_SHORT_FBWA = 2,
40
FS_ACTION_SHORT_DISABLED = 3,
41
FS_ACTION_SHORT_FBWB = 4,
42
};
43
44
enum failsafe_action_long {
45
FS_ACTION_LONG_CONTINUE = 0,
46
FS_ACTION_LONG_RTL = 1,
47
FS_ACTION_LONG_GLIDE = 2,
48
FS_ACTION_LONG_PARACHUTE = 3,
49
FS_ACTION_LONG_AUTO = 4,
50
FS_ACTION_LONG_AUTOLAND = 5,
51
};
52
53
// type of stick mixing enabled
54
enum class StickMixing {
55
NONE = 0,
56
FBW = 1,
57
DIRECT_REMOVED = 2,
58
VTOL_YAW = 3,
59
};
60
61
// values for RTL_AUTOLAND
62
enum class RtlAutoland {
63
RTL_DISABLE = 0,
64
RTL_THEN_DO_LAND_START = 1,
65
RTL_IMMEDIATE_DO_LAND_START = 2,
66
NO_RTL_GO_AROUND = 3,
67
DO_RETURN_PATH_START = 4,
68
};
69
70
// PID broadcast bitmask
71
enum tuning_pid_bits {
72
TUNING_BITS_ROLL = (1 << 0),
73
TUNING_BITS_PITCH = (1 << 1),
74
TUNING_BITS_YAW = (1 << 2),
75
TUNING_BITS_STEER = (1 << 3),
76
TUNING_BITS_LAND = (1 << 4),
77
TUNING_BITS_ACCZ = (1 << 5),
78
TUNING_BITS_END // dummy just used for static checking
79
};
80
81
static_assert(TUNING_BITS_END <= (1 << 24) + 1, "Tuning bit mask is too large to be set by MAVLink");
82
83
// Logging message types - only 32 messages are available to the vehicle here.
84
enum log_messages {
85
LOG_CTUN_MSG,
86
LOG_NTUN_MSG,
87
LOG_STATUS_MSG,
88
LOG_QTUN_MSG,
89
LOG_PIQR_MSG,
90
LOG_PIQP_MSG,
91
LOG_PIQY_MSG,
92
LOG_PIQA_MSG,
93
LOG_PIDG_MSG,
94
LOG_AETR_MSG,
95
LOG_OFG_MSG,
96
LOG_TSIT_MSG,
97
LOG_TILT_MSG,
98
};
99
100
#define MASK_LOG_ATTITUDE_FAST (1<<0)
101
#define MASK_LOG_ATTITUDE_MED (1<<1)
102
#define MASK_LOG_GPS (1<<2)
103
#define MASK_LOG_PM (1<<3)
104
#define MASK_LOG_CTUN (1<<4)
105
#define MASK_LOG_NTUN (1<<5)
106
//#define MASK_LOG_MODE (1<<6) // no longer used
107
#define MASK_LOG_IMU (1<<7)
108
#define MASK_LOG_CMD (1<<8)
109
#define MASK_LOG_CURRENT (1<<9)
110
#define MASK_LOG_COMPASS (1<<10)
111
#define MASK_LOG_TECS (1<<11)
112
#define MASK_LOG_CAMERA (1<<12)
113
#define MASK_LOG_RC (1<<13)
114
#define MASK_LOG_SONAR (1<<14)
115
// #define MASK_LOG_ARM_DISARM (1<<15)
116
#define MASK_LOG_IMU_RAW (1UL<<19)
117
#define MASK_LOG_ATTITUDE_FULLRATE (1U<<20)
118
#define MASK_LOG_VIDEO_STABILISATION (1UL<<21)
119
#define MASK_LOG_NOTCH_FULLRATE (1UL<<22)
120
121
enum {
122
CRASH_DETECT_ACTION_BITMASK_DISABLED = 0,
123
CRASH_DETECT_ACTION_BITMASK_DISARM = (1<<0),
124
// note: next enum will be (1<<1), then (1<<2), then (1<<3)
125
};
126
127
enum {
128
USE_REVERSE_THRUST_NEVER = 0,
129
USE_REVERSE_THRUST_AUTO_ALWAYS = (1<<0),
130
USE_REVERSE_THRUST_AUTO_LAND_APPROACH = (1<<1),
131
USE_REVERSE_THRUST_AUTO_LOITER_TO_ALT = (1<<2),
132
USE_REVERSE_THRUST_AUTO_LOITER_ALL = (1<<3),
133
USE_REVERSE_THRUST_AUTO_WAYPOINT = (1<<4),
134
USE_REVERSE_THRUST_LOITER = (1<<5),
135
USE_REVERSE_THRUST_RTL = (1<<6),
136
USE_REVERSE_THRUST_CIRCLE = (1<<7),
137
USE_REVERSE_THRUST_CRUISE = (1<<8),
138
USE_REVERSE_THRUST_FBWB = (1<<9),
139
USE_REVERSE_THRUST_GUIDED = (1<<10),
140
USE_REVERSE_THRUST_AUTO_LANDING_PATTERN = (1<<11),
141
USE_REVERSE_THRUST_FBWA = (1<<12),
142
USE_REVERSE_THRUST_ACRO = (1<<13),
143
USE_REVERSE_THRUST_STABILIZE = (1<<14),
144
USE_REVERSE_THRUST_THERMAL = (1<<15),
145
};
146
147
enum FlightOptions {
148
DIRECT_RUDDER_ONLY = (1 << 0),
149
CRUISE_TRIM_THROTTLE = (1 << 1),
150
DISABLE_TOFF_ATTITUDE_CHK = (1 << 2),
151
CRUISE_TRIM_AIRSPEED = (1 << 3),
152
CLIMB_BEFORE_TURN = (1 << 4),
153
ACRO_YAW_DAMPER = (1 << 5),
154
SURPRESS_TKOFF_SCALING = (1<<6),
155
ENABLE_DEFAULT_AIRSPEED = (1<<7),
156
GCS_REMOVE_TRIM_PITCH = (1 << 8),
157
OSD_REMOVE_TRIM_PITCH = (1 << 9),
158
CENTER_THROTTLE_TRIM = (1<<10),
159
DISABLE_GROUND_PID_SUPPRESSION = (1<<11),
160
ENABLE_LOITER_ALT_CONTROL = (1<<12),
161
INDICATE_WAITING_FOR_RUDDER_NEUTRAL = (1<<13),
162
IMMEDIATE_CLIMB_IN_AUTO = (1<<14),
163
};
164
165
enum CrowFlapOptions {
166
FLYINGWING = (1 << 0),
167
FULLSPAN = (1 << 1),
168
PROGRESSIVE_CROW = (1 << 2),
169
};
170
171
172
enum guided_heading_type_t {
173
GUIDED_HEADING_NONE = 0, // no heading track
174
GUIDED_HEADING_COG, // maintain ground track
175
GUIDED_HEADING_HEADING, // maintain a heading
176
};
177
178
179
enum class AirMode {
180
OFF,
181
ON,
182
ASSISTED_FLIGHT_ONLY,
183
};
184
185
enum class FenceAutoEnable : uint8_t {
186
OFF=0,
187
Auto=1,
188
AutoDisableFloorOnly=2,
189
WhenArmed=3
190
};
191
192