Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BoardConfig/AP_BoardConfig.h
9573 views
1
#pragma once
2
3
#include "AP_BoardConfig_config.h"
4
#include <AP_Common/AP_Common.h>
5
#include <AP_Param/AP_Param.h>
6
#include <AP_RTC/AP_RTC.h>
7
#include <AC_PID/AC_PI.h>
8
#include <AP_Radio/AP_Radio_config.h>
9
10
#if AP_RADIO_ENABLED
11
#include <AP_Radio/AP_Radio.h>
12
#endif
13
14
extern "C" typedef int (*main_fn_t)(int argc, char **);
15
16
class AP_BoardConfig {
17
public:
18
AP_BoardConfig();
19
20
/* Do not allow copies */
21
CLASS_NO_COPY(AP_BoardConfig);
22
23
// singleton support
24
static AP_BoardConfig *get_singleton(void) {
25
return _singleton;
26
}
27
28
void init(void);
29
void init_safety(void);
30
31
static const struct AP_Param::GroupInfo var_info[];
32
33
// notify user of a fatal startup error related to available sensors.
34
static void config_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;
35
36
// notify user of a non-fatal startup error related to allocation failures.
37
static void allocation_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;
38
39
// permit other libraries (in particular, GCS_MAVLink) to detect
40
// that we're never going to boot properly:
41
static bool in_config_error(void) { return _in_error_loop; }
42
43
// valid types for BRD_TYPE: these values need to be in sync with the
44
// values from the param description
45
enum px4_board_type {
46
BOARD_TYPE_UNKNOWN = -1,
47
PX4_BOARD_AUTO = 0,
48
PX4_BOARD_PX4V1 = 1,
49
PX4_BOARD_PIXHAWK = 2,
50
PX4_BOARD_PIXHAWK2 = 3,
51
// PX4_BOARD_PIXRACER = 4,
52
PX4_BOARD_PHMINI = 5,
53
PX4_BOARD_PH2SLIM = 6,
54
PX4_BOARD_AEROFC = 13,
55
// PX4_BOARD_PIXHAWK_PRO = 14,
56
PX4_BOARD_AUAV21 = 20,
57
// PX4_BOARD_PCNC1 = 21,
58
// PX4_BOARD_MINDPXV2 = 22,
59
// PX4_BOARD_SP01 = 23,
60
// PX4_BOARD_FMUV5 = 24,
61
// VRX_BOARD_BRAIN51 = 30,
62
// VRX_BOARD_BRAIN52 = 32,
63
// VRX_BOARD_BRAIN52E = 33,
64
// VRX_BOARD_UBRAIN51 = 34,
65
// VRX_BOARD_UBRAIN52 = 35,
66
// VRX_BOARD_CORE10 = 36,
67
// VRX_BOARD_BRAIN54 = 38,
68
PX4_BOARD_FMUV6 = 39,
69
FMUV6_BOARD_HOLYBRO_6X = 40,
70
FMUV6_BOARD_CUAV_6X = 41,
71
FMUV6_BOARD_HOLYBRO_6X_REV6 = 42,
72
FMUV6_BOARD_HOLYBRO_6X_45686 = 43,
73
PX4_BOARD_OLDDRIVERS = 100,
74
};
75
76
// set default value for BRD_SAFETY_MASK
77
void set_default_safety_ignore_mask(uint32_t mask);
78
79
static enum px4_board_type get_board_type(void) {
80
#if AP_FEATURE_BOARD_DETECT
81
return px4_configured_board;
82
#else
83
return BOARD_TYPE_UNKNOWN;
84
#endif
85
}
86
87
// ask if IOMCU is enabled. This is a uint8_t to allow
88
// developer debugging by setting BRD_IO_ENABLE=100 to avoid the
89
// crc check of IO firmware on startup
90
static uint8_t io_enabled(void) {
91
#if HAL_WITH_IO_MCU
92
return _singleton?uint8_t(_singleton->state.io_enable.get()):0;
93
#else
94
return 0;
95
#endif
96
}
97
98
static bool io_dshot(void) {
99
#if HAL_WITH_IO_MCU_DSHOT
100
return io_enabled() && _singleton?_singleton->state.io_dshot.get():false;
101
#else
102
return false;
103
#endif
104
}
105
106
// get alternative config selection
107
uint8_t get_alt_config(void) {
108
return uint8_t(_alt_config.get());
109
}
110
111
enum board_safety_button_option {
112
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF= (1 << 0),
113
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON= (1 << 1),
114
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED= (1 << 2),
115
BOARD_SAFETY_OPTION_SAFETY_ON_DISARM= (1 << 3),
116
};
117
118
// return safety button options. Bits are in enum board_safety_button_option
119
uint16_t get_safety_button_options(void) const {
120
return uint16_t(state.safety_option.get());
121
}
122
123
// return the value of BRD_SAFETY_MASK
124
uint16_t get_safety_mask(void) const {
125
return uint32_t(state.ignore_safety_channels.get());
126
}
127
128
uint32_t get_serial_number() const {
129
return (uint32_t)vehicleSerialNumber.get();
130
}
131
132
#if HAL_HAVE_BOARD_VOLTAGE
133
// get minimum board voltage
134
static float get_minimum_board_voltage(void) {
135
return _singleton?_singleton->_vbus_min.get():0;
136
}
137
#endif
138
139
#if HAL_HAVE_SERVO_VOLTAGE
140
// get minimum servo voltage
141
static float get_minimum_servo_voltage(void) {
142
return _singleton?_singleton->_vservo_min.get():0;
143
}
144
#endif
145
146
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
147
static uint8_t get_sdcard_slowdown(void) {
148
return _singleton?_singleton->_sdcard_slowdown.get():0;
149
}
150
#endif
151
152
#if AP_CPU_IDLE_STATS_ENABLED
153
static bool use_idle_stats(void) {
154
return _singleton?_singleton->state.idle_stats.get():0;
155
}
156
#endif
157
158
enum board_options {
159
BOARD_OPTION_WATCHDOG = (1 << 0),
160
DISABLE_FTP = (1<<1),
161
ALLOW_SET_INTERNAL_PARM = (1<<2),
162
BOARD_OPTION_DEBUG_ENABLE = (1<<3),
163
UNLOCK_FLASH = (1<<4),
164
WRITE_PROTECT_FLASH = (1<<5),
165
WRITE_PROTECT_BOOTLOADER = (1<<6),
166
SKIP_BOARD_VALIDATION = (1<<7),
167
DISABLE_ARMING_GPIO = (1<<8),
168
IO_SAFETY_PINS_AS_PROFILED = (1<<9),
169
};
170
171
//return true if arming gpio output is disabled
172
static bool arming_gpio_disabled(void) {
173
return _singleton?(_singleton->_options & DISABLE_ARMING_GPIO)!=0:1;
174
}
175
176
#ifndef HAL_ARM_GPIO_POL_INVERT
177
#define HAL_ARM_GPIO_POL_INVERT 0
178
#endif
179
180
// return true if ftp is disabled
181
static bool ftp_disabled(void) {
182
return _singleton?(_singleton->_options & DISABLE_FTP)!=0:1;
183
}
184
185
// return true if watchdog enabled
186
static bool watchdog_enabled(void) {
187
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:HAL_WATCHDOG_ENABLED_DEFAULT;
188
}
189
190
// return true if flash should be unlocked
191
static bool unlock_flash(void) {
192
return _singleton && (_singleton->_options & UNLOCK_FLASH) != 0;
193
}
194
195
// return true if flash should be write protected
196
static bool protect_flash(void) {
197
return _singleton && (_singleton->_options & WRITE_PROTECT_FLASH) != 0;
198
}
199
200
// return true if bootloader should be write protected
201
static bool protect_bootloader(void) {
202
return _singleton && (_singleton->_options & WRITE_PROTECT_BOOTLOADER) != 0;
203
}
204
205
// return true if we allow setting of internal parameters (for developers)
206
static bool allow_set_internal_parameters(void) {
207
return _singleton?(_singleton->_options & ALLOW_SET_INTERNAL_PARM)!=0:false;
208
}
209
210
#if HAL_WITH_IO_MCU
211
static bool use_safety_as_led(void) {
212
return _singleton?(_singleton->_options & IO_SAFETY_PINS_AS_PROFILED)!=0:false;
213
}
214
#endif
215
216
// handle press of safety button. Return true if safety state
217
// should be toggled
218
bool safety_button_handle_pressed(uint8_t press_count);
219
220
#if HAL_HAVE_IMU_HEATER
221
void set_imu_temp(float current_temp_c);
222
223
// heater duty cycle is as a percentage (0 to 100)
224
float get_heater_duty_cycle(void) const {
225
return heater.output;
226
}
227
228
// getters for current temperature and min arming temperature, return false if heater disabled
229
bool get_board_heater_temperature(float &temperature) const;
230
bool get_board_heater_arming_temperature(int8_t &temperature) const;
231
#endif
232
233
#if AP_SDCARD_STORAGE_ENABLED
234
// return number of kb of mission storage to use on microSD
235
static uint16_t get_sdcard_mission_kb(void) {
236
return _singleton? _singleton->sdcard_storage.mission_kb.get() : 0;
237
}
238
239
// return number of kb of fence storage to use on microSD
240
static uint16_t get_sdcard_fence_kb(void) {
241
return _singleton? _singleton->sdcard_storage.fence_kb.get() : 0;
242
}
243
#endif
244
245
private:
246
static AP_BoardConfig *_singleton;
247
248
AP_Int32 vehicleSerialNumber;
249
250
struct {
251
AP_Int8 safety_enable;
252
AP_Int16 safety_option;
253
AP_Int32 ignore_safety_channels;
254
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
255
AP_Int8 ser_rtscts[9];
256
AP_Int8 sbus_out_rate;
257
#endif
258
#if AP_CPU_IDLE_STATS_ENABLED
259
AP_Int8 idle_stats;
260
#endif
261
AP_Int8 board_type;
262
AP_Int8 io_enable;
263
AP_Int8 io_dshot;
264
} state;
265
266
#if AP_SDCARD_STORAGE_ENABLED
267
struct {
268
AP_Int16 mission_kb;
269
AP_Int16 fence_kb;
270
} sdcard_storage;
271
#endif
272
273
#if AP_FEATURE_BOARD_DETECT
274
static enum px4_board_type px4_configured_board;
275
276
void board_setup_drivers(void);
277
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
278
bool spi_check_register_inv2(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
279
void validate_board_type(void);
280
void board_autodetect(void);
281
void detect_fmuv6_variant(void);
282
bool check_ms5611(const char* devname);
283
284
#endif // AP_FEATURE_BOARD_DETECT
285
286
void board_init_safety(void);
287
void board_init_debug(void);
288
289
void board_setup_uart(void);
290
void board_setup_sbus(void);
291
void board_setup(void);
292
293
// common method to throw errors
294
static void throw_error(const char *err_str, const char *fmt, va_list arg) NORETURN;
295
296
static bool _in_error_loop;
297
298
#if HAL_HAVE_IMU_HEATER
299
struct {
300
AC_PI pi_controller;
301
AP_Int8 imu_target_temperature;
302
uint32_t last_update_ms;
303
uint16_t count;
304
float sum;
305
float output;
306
uint32_t last_log_ms;
307
float temperature;
308
AP_Int8 imu_arming_temperature_margin_low;
309
} heater;
310
#endif
311
312
#if AP_RADIO_ENABLED
313
// direct attached radio
314
AP_Radio _radio;
315
#endif
316
317
#if AP_RTC_ENABLED
318
// real-time-clock; private because access is via the singleton
319
AP_RTC rtc;
320
#endif
321
322
#if HAL_HAVE_BOARD_VOLTAGE
323
AP_Float _vbus_min;
324
#endif
325
326
#if HAL_HAVE_SERVO_VOLTAGE
327
AP_Float _vservo_min;
328
#endif
329
330
AP_Int8 _pwm_volt_sel;
331
332
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
333
AP_Int8 _sdcard_slowdown;
334
#endif
335
336
AP_Int16 _boot_delay_ms;
337
338
AP_Int32 _options;
339
340
AP_Int8 _alt_config;
341
};
342
343
namespace AP {
344
AP_BoardConfig *boardConfig(void);
345
};
346
347