Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/config.h
9697 views
1
//
2
#pragma once
3
4
//////////////////////////////////////////////////////////////////////////////
5
//
6
// Default and automatic configuration details.
7
//
8
//
9
#include "defines.h"
10
11
//////////////////////////////////////////////////////////////////////////////
12
//////////////////////////////////////////////////////////////////////////////
13
// HARDWARE CONFIGURATION AND CONNECTIONS
14
//////////////////////////////////////////////////////////////////////////////
15
//////////////////////////////////////////////////////////////////////////////
16
17
#ifndef CONFIG_HAL_BOARD
18
#error CONFIG_HAL_BOARD must be defined to build Blimp
19
#endif
20
21
#ifndef ARMING_DELAY_SEC
22
# define ARMING_DELAY_SEC 2.0f
23
#endif
24
25
//////////////////////////////////////////////////////////////////////////////
26
// PWM control
27
// default RC speed in Hz
28
#ifndef RC_FAST_SPEED
29
# define RC_FAST_SPEED 490
30
#endif
31
32
#ifndef MAV_SYSTEM_ID
33
# define MAV_SYSTEM_ID 1
34
#endif
35
36
// prearm GPS hdop check
37
#ifndef GPS_HDOP_GOOD_DEFAULT
38
# define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled
39
#endif
40
41
// Radio failsafe while using RC_override
42
#ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
43
# define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 1000 // RC Radio failsafe triggers after 1 second while using RC_override from ground station
44
#endif
45
46
// missing terrain data failsafe
47
#ifndef FS_TERRAIN_TIMEOUT_MS
48
#define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL)
49
#endif
50
51
// pre-arm baro vs inertial nav max alt disparity
52
#ifndef PREARM_MAX_ALT_DISPARITY_CM
53
# define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters
54
#endif
55
56
//////////////////////////////////////////////////////////////////////////////
57
// EKF Failsafe
58
#ifndef FS_EKF_ACTION_DEFAULT
59
# define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_LAND // EKF failsafe triggers land by default
60
#endif
61
#ifndef FS_EKF_THRESHOLD_DEFAULT
62
# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
63
#endif
64
65
//////////////////////////////////////////////////////////////////////////////
66
// FLIGHT_MODE
67
//
68
#ifndef FLIGHT_MODE_1
69
# define FLIGHT_MODE_1 Mode::Number::MANUAL
70
#endif
71
#ifndef FLIGHT_MODE_2
72
# define FLIGHT_MODE_2 Mode::Number::MANUAL
73
#endif
74
#ifndef FLIGHT_MODE_3
75
# define FLIGHT_MODE_3 Mode::Number::MANUAL
76
#endif
77
#ifndef FLIGHT_MODE_4
78
# define FLIGHT_MODE_4 Mode::Number::MANUAL
79
#endif
80
#ifndef FLIGHT_MODE_5
81
# define FLIGHT_MODE_5 Mode::Number::MANUAL
82
#endif
83
#ifndef FLIGHT_MODE_6
84
# define FLIGHT_MODE_6 Mode::Number::MANUAL
85
#endif
86
87
//////////////////////////////////////////////////////////////////////////////
88
// Throttle Failsafe
89
//
90
#ifndef FS_THR_VALUE_DEFAULT
91
# define FS_THR_VALUE_DEFAULT 975
92
#endif
93
94
//////////////////////////////////////////////////////////////////////////////
95
// Throttle control defaults
96
//
97
#ifndef THR_DZ_DEFAULT
98
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
99
#endif
100
101
#ifndef AUTO_DISARMING_DELAY
102
# define AUTO_DISARMING_DELAY 10
103
#endif
104
105
// Default logging bitmask
106
#ifndef DEFAULT_LOG_BITMASK
107
# define DEFAULT_LOG_BITMASK \
108
MASK_LOG_ATTITUDE_MED | \
109
MASK_LOG_GPS | \
110
MASK_LOG_PM | \
111
MASK_LOG_CTUN | \
112
MASK_LOG_NTUN | \
113
MASK_LOG_RCIN | \
114
MASK_LOG_IMU | \
115
MASK_LOG_CMD | \
116
MASK_LOG_CURRENT | \
117
MASK_LOG_RCOUT | \
118
MASK_LOG_OPTFLOW | \
119
MASK_LOG_COMPASS | \
120
MASK_LOG_CAMERA | \
121
MASK_LOG_MOTBATT
122
#endif
123
124
#ifndef CH_MODE_DEFAULT
125
# define CH_MODE_DEFAULT 5
126
#endif
127
128
#ifndef HAL_FRAME_TYPE_DEFAULT
129
#define HAL_FRAME_TYPE_DEFAULT Fins::MOTOR_FRAME_TYPE_AIRFISH
130
#endif
131
132