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/libraries/AP_BoardConfig/AP_BoardConfig.h
Views: 1798
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
enum board_options {
153
BOARD_OPTION_WATCHDOG = (1 << 0),
154
DISABLE_FTP = (1<<1),
155
ALLOW_SET_INTERNAL_PARM = (1<<2),
156
BOARD_OPTION_DEBUG_ENABLE = (1<<3),
157
UNLOCK_FLASH = (1<<4),
158
WRITE_PROTECT_FLASH = (1<<5),
159
WRITE_PROTECT_BOOTLOADER = (1<<6),
160
SKIP_BOARD_VALIDATION = (1<<7),
161
DISABLE_ARMING_GPIO = (1<<8),
162
IO_SAFETY_PINS_AS_PROFILED = (1<<9),
163
};
164
165
//return true if arming gpio output is disabled
166
static bool arming_gpio_disabled(void) {
167
return _singleton?(_singleton->_options & DISABLE_ARMING_GPIO)!=0:1;
168
}
169
170
#ifndef HAL_ARM_GPIO_POL_INVERT
171
#define HAL_ARM_GPIO_POL_INVERT 0
172
#endif
173
174
// return true if ftp is disabled
175
static bool ftp_disabled(void) {
176
return _singleton?(_singleton->_options & DISABLE_FTP)!=0:1;
177
}
178
179
// return true if watchdog enabled
180
static bool watchdog_enabled(void) {
181
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:HAL_WATCHDOG_ENABLED_DEFAULT;
182
}
183
184
// return true if flash should be unlocked
185
static bool unlock_flash(void) {
186
return _singleton && (_singleton->_options & UNLOCK_FLASH) != 0;
187
}
188
189
// return true if flash should be write protected
190
static bool protect_flash(void) {
191
return _singleton && (_singleton->_options & WRITE_PROTECT_FLASH) != 0;
192
}
193
194
// return true if bootloader should be write protected
195
static bool protect_bootloader(void) {
196
return _singleton && (_singleton->_options & WRITE_PROTECT_BOOTLOADER) != 0;
197
}
198
199
// return true if we allow setting of internal parameters (for developers)
200
static bool allow_set_internal_parameters(void) {
201
return _singleton?(_singleton->_options & ALLOW_SET_INTERNAL_PARM)!=0:false;
202
}
203
204
#if HAL_WITH_IO_MCU
205
static bool use_safety_as_led(void) {
206
return _singleton?(_singleton->_options & IO_SAFETY_PINS_AS_PROFILED)!=0:false;
207
}
208
#endif
209
210
// handle press of safety button. Return true if safety state
211
// should be toggled
212
bool safety_button_handle_pressed(uint8_t press_count);
213
214
#if HAL_HAVE_IMU_HEATER
215
void set_imu_temp(float current_temp_c);
216
217
// heater duty cycle is as a percentage (0 to 100)
218
float get_heater_duty_cycle(void) const {
219
return heater.output;
220
}
221
222
// getters for current temperature and min arming temperature, return false if heater disabled
223
bool get_board_heater_temperature(float &temperature) const;
224
bool get_board_heater_arming_temperature(int8_t &temperature) const;
225
#endif
226
227
#if AP_SDCARD_STORAGE_ENABLED
228
// return number of kb of mission storage to use on microSD
229
static uint16_t get_sdcard_mission_kb(void) {
230
return _singleton? _singleton->sdcard_storage.mission_kb.get() : 0;
231
}
232
233
// return number of kb of fence storage to use on microSD
234
static uint16_t get_sdcard_fence_kb(void) {
235
return _singleton? _singleton->sdcard_storage.fence_kb.get() : 0;
236
}
237
#endif
238
239
private:
240
static AP_BoardConfig *_singleton;
241
242
AP_Int32 vehicleSerialNumber;
243
244
struct {
245
AP_Int8 safety_enable;
246
AP_Int16 safety_option;
247
AP_Int32 ignore_safety_channels;
248
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
249
AP_Int8 ser_rtscts[6];
250
AP_Int8 sbus_out_rate;
251
#endif
252
AP_Int8 board_type;
253
AP_Int8 io_enable;
254
AP_Int8 io_dshot;
255
} state;
256
257
#if AP_SDCARD_STORAGE_ENABLED
258
struct {
259
AP_Int16 mission_kb;
260
AP_Int16 fence_kb;
261
} sdcard_storage;
262
#endif
263
264
#if AP_FEATURE_BOARD_DETECT
265
static enum px4_board_type px4_configured_board;
266
267
void board_setup_drivers(void);
268
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
269
bool spi_check_register_inv2(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
270
void validate_board_type(void);
271
void board_autodetect(void);
272
void detect_fmuv6_variant(void);
273
bool check_ms5611(const char* devname);
274
275
#endif // AP_FEATURE_BOARD_DETECT
276
277
void board_init_safety(void);
278
void board_init_debug(void);
279
280
void board_setup_uart(void);
281
void board_setup_sbus(void);
282
void board_setup(void);
283
284
// common method to throw errors
285
static void throw_error(const char *err_str, const char *fmt, va_list arg) NORETURN;
286
287
static bool _in_error_loop;
288
289
#if HAL_HAVE_IMU_HEATER
290
struct {
291
AC_PI pi_controller;
292
AP_Int8 imu_target_temperature;
293
uint32_t last_update_ms;
294
uint16_t count;
295
float sum;
296
float output;
297
uint32_t last_log_ms;
298
float temperature;
299
AP_Int8 imu_arming_temperature_margin_low;
300
} heater;
301
#endif
302
303
#if AP_RADIO_ENABLED
304
// direct attached radio
305
AP_Radio _radio;
306
#endif
307
308
#if AP_RTC_ENABLED
309
// real-time-clock; private because access is via the singleton
310
AP_RTC rtc;
311
#endif
312
313
#if HAL_HAVE_BOARD_VOLTAGE
314
AP_Float _vbus_min;
315
#endif
316
317
#if HAL_HAVE_SERVO_VOLTAGE
318
AP_Float _vservo_min;
319
#endif
320
321
AP_Int8 _pwm_volt_sel;
322
323
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
324
AP_Int8 _sdcard_slowdown;
325
#endif
326
327
AP_Int16 _boot_delay_ms;
328
329
AP_Int32 _options;
330
331
AP_Int8 _alt_config;
332
};
333
334
namespace AP {
335
AP_BoardConfig *boardConfig(void);
336
};
337
338