Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_BoardConfig/AP_BoardConfig.cpp
9415 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
* AP_BoardConfig - board specific configuration
17
*/
18
19
#include "AP_BoardConfig.h"
20
21
#include <AP_Common/AP_Common.h>
22
#include <AP_HAL/AP_HAL.h>
23
#include <AP_Math/AP_Math.h>
24
#include <AP_RTC/AP_RTC.h>
25
#include <AP_Vehicle/AP_Vehicle_Type.h>
26
#include <GCS_MAVLink/GCS.h>
27
#include <AP_Filesystem/AP_Filesystem.h>
28
#include <GCS_MAVLink/GCS.h>
29
#include <GCS_MAVLink/GCS_MAVLink.h>
30
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
31
32
#include <stdio.h>
33
34
#ifndef BOARD_TYPE_DEFAULT
35
#define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
36
#endif
37
38
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
39
#ifndef BOARD_SER1_RTSCTS_DEFAULT
40
# define BOARD_SER1_RTSCTS_DEFAULT 2
41
#endif
42
#ifndef BOARD_TYPE_DEFAULT
43
# define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
44
#endif
45
#endif
46
47
#ifndef BOARD_SAFETY_ENABLE_DEFAULT
48
#if defined(HAL_GPIO_PIN_SAFETY_IN)
49
// have safety startup enabled if we have a safety pin
50
# define BOARD_SAFETY_ENABLE_DEFAULT 1
51
#elif defined(HAL_WITH_IO_MCU)
52
// if we have an IOMCU then enable by default
53
# define BOARD_SAFETY_ENABLE_DEFAULT HAL_WITH_IO_MCU
54
#else
55
# define BOARD_SAFETY_ENABLE_DEFAULT 0
56
#endif
57
#endif
58
59
#ifndef HAL_IMU_TEMP_DEFAULT
60
#define HAL_IMU_TEMP_DEFAULT -1 // disabled
61
#endif
62
63
#ifndef HAL_IMU_TEMP_MARGIN_LOW_DEFAULT
64
#define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 0 // disabled
65
#endif
66
67
#ifndef BOARD_SAFETY_OPTION_DEFAULT
68
# define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)
69
#endif
70
#ifndef BOARD_SAFETY_ENABLE
71
# define BOARD_SAFETY_ENABLE 1
72
#endif
73
74
#ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN
75
#define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
76
#endif
77
78
#ifndef HAL_BRD_OPTIONS_DEFAULT
79
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !APM_BUILD_TYPE(APM_BUILD_Replay)
80
#ifdef HAL_DEBUG_BUILD
81
#define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG | BOARD_OPTION_DEBUG_ENABLE
82
#else
83
#define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG
84
#endif
85
#else
86
#define HAL_BRD_OPTIONS_DEFAULT 0
87
#endif
88
#endif
89
90
#ifndef HAL_DEFAULT_BOOT_DELAY
91
#define HAL_DEFAULT_BOOT_DELAY 0
92
#endif
93
94
extern const AP_HAL::HAL& hal;
95
AP_BoardConfig *AP_BoardConfig::_singleton;
96
97
// constructor
98
AP_BoardConfig::AP_BoardConfig()
99
#if HAL_HAVE_IMU_HEATER
100
// initialise heater PI controller. Note we do this in the cpp file
101
// for ccache efficiency
102
: heater{{HAL_IMUHEAT_P_DEFAULT, HAL_IMUHEAT_I_DEFAULT, 70},}
103
#endif
104
{
105
_singleton = this;
106
AP_Param::setup_object_defaults(this, var_info);
107
};
108
109
// table of user settable parameters
110
const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
111
112
// index 0 was used by PWM_COUNT
113
114
#if AP_FEATURE_RTSCTS
115
#ifdef HAL_HAVE_RTSCTS_SERIAL1
116
// @Param: SER1_RTSCTS
117
// @DisplayName: Serial 1 flow control
118
// @Description: Enable flow control on serial 1 (telemetry 1). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled.
119
// @Values: 0:Disabled,1:Enabled,2:Auto,3:RS-485 Driver enable RTS pin
120
// @RebootRequired: True
121
// @User: Advanced
122
AP_GROUPINFO("SER1_RTSCTS", 1, AP_BoardConfig, state.ser_rtscts[1], BOARD_SER1_RTSCTS_DEFAULT),
123
#endif
124
125
#ifdef HAL_HAVE_RTSCTS_SERIAL2
126
// @Param: SER2_RTSCTS
127
// @CopyFieldsFrom: BRD_SER1_RTSCTS
128
// @DisplayName: Serial 2 flow control
129
// @Description: Enable flow control on serial 2 (telemetry 2). You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
130
AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser_rtscts[2], 2),
131
#endif
132
133
#ifdef HAL_HAVE_RTSCTS_SERIAL3
134
// @Param: SER3_RTSCTS
135
// @CopyFieldsFrom: BRD_SER1_RTSCTS
136
// @DisplayName: Serial 3 flow control
137
// @Description: Enable flow control on serial 3. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
138
AP_GROUPINFO("SER3_RTSCTS", 26, AP_BoardConfig, state.ser_rtscts[3], 2),
139
#endif
140
141
#ifdef HAL_HAVE_RTSCTS_SERIAL4
142
// @Param: SER4_RTSCTS
143
// @CopyFieldsFrom: BRD_SER1_RTSCTS
144
// @DisplayName: Serial 4 flow control
145
// @Description: Enable flow control on serial 4. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
146
AP_GROUPINFO("SER4_RTSCTS", 27, AP_BoardConfig, state.ser_rtscts[4], 2),
147
#endif
148
149
#ifdef HAL_HAVE_RTSCTS_SERIAL5
150
// @Param: SER5_RTSCTS
151
// @CopyFieldsFrom: BRD_SER1_RTSCTS
152
// @DisplayName: Serial 5 flow control
153
// @Description: Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
154
AP_GROUPINFO("SER5_RTSCTS", 25, AP_BoardConfig, state.ser_rtscts[5], 2),
155
#endif
156
157
#ifdef HAL_HAVE_RTSCTS_SERIAL6
158
// @Param: SER6_RTSCTS
159
// @CopyFieldsFrom: BRD_SER1_RTSCTS
160
// @DisplayName: Serial 6 flow control
161
// @Description: Enable flow control on serial 6. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
162
AP_GROUPINFO("SER6_RTSCTS", 30, AP_BoardConfig, state.ser_rtscts[6], 2),
163
#endif
164
165
#ifdef HAL_HAVE_RTSCTS_SERIAL7
166
// @Param: SER7_RTSCTS
167
// @CopyFieldsFrom: BRD_SER1_RTSCTS
168
// @DisplayName: Serial 7 flow control
169
// @Description: Enable flow control on serial 7. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
170
AP_GROUPINFO("SER7_RTSCTS", 31, AP_BoardConfig, state.ser_rtscts[7], 2),
171
#endif
172
173
#ifdef HAL_HAVE_RTSCTS_SERIAL8
174
// @Param: SER8_RTSCTS
175
// @CopyFieldsFrom: BRD_SER8_RTSCTS
176
// @DisplayName: Serial 8 flow control
177
// @Description: Enable flow control on serial 8. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
178
AP_GROUPINFO("SER8_RTSCTS", 32, AP_BoardConfig, state.ser_rtscts[8], 2),
179
#endif
180
#endif
181
182
// @Param: SAFETY_DEFLT
183
// @DisplayName: Sets default state of the safety switch
184
// @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
185
// @Values: 0:Disabled,1:Enabled
186
// @RebootRequired: True
187
// @User: Standard
188
AP_GROUPINFO("SAFETY_DEFLT", 3, AP_BoardConfig, state.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT),
189
190
#if AP_FEATURE_SBUS_OUT
191
// @Param: SBUS_OUT
192
// @DisplayName: SBUS output rate
193
// @Description: This sets the SBUS output frame rate in Hz
194
// @Values: 0:Disabled,1:50Hz,2:75Hz,3:100Hz,4:150Hz,5:200Hz,6:250Hz,7:300Hz
195
// @RebootRequired: True
196
// @User: Advanced
197
AP_GROUPINFO("SBUS_OUT", 4, AP_BoardConfig, state.sbus_out_rate, 0),
198
#endif
199
200
// @Param: SERIAL_NUM
201
// @DisplayName: User-defined serial number
202
// @Description: User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
203
// @Range: -8388608 8388607
204
// @User: Standard
205
AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0),
206
207
// @Param: SAFETY_MASK
208
// @DisplayName: Outputs which ignore the safety switch state
209
// @Description: A bitmask which controls what outputs can move while the safety switch has not been pressed
210
// @Bitmask: 0:Output1
211
// @Bitmask: 1:Output2
212
// @Bitmask: 2:Output3
213
// @Bitmask: 3:Output4
214
// @Bitmask: 4:Output5
215
// @Bitmask: 5:Output6
216
// @Bitmask: 6:Output7
217
// @Bitmask: 7:Output8
218
// @Bitmask: 8:Output9
219
// @Bitmask: 9:Output10
220
// @Bitmask: 10:Output11
221
// @Bitmask: 11:Output12
222
// @Bitmask: 12:Output13
223
// @Bitmask: 13:Output14
224
// @Bitmask: 14:Output15
225
// @Bitmask: 15:Output16
226
// @Bitmask: 16:Output17
227
// @Bitmask: 17:Output18
228
// @Bitmask: 18:Output19
229
// @Bitmask: 19:Output20
230
// @Bitmask: 20:Output21
231
// @Bitmask: 21:Output22
232
// @Bitmask: 22:Output23
233
// @Bitmask: 23:Output24
234
// @Bitmask: 24:Output25
235
// @Bitmask: 25:Output26
236
// @Bitmask: 26:Output27
237
// @Bitmask: 27:Output28
238
// @Bitmask: 28:Output29
239
// @Bitmask: 29:Output30
240
// @Bitmask: 30:Output31
241
// @Bitmask: 31:Output32
242
// @RebootRequired: True
243
// @User: Advanced
244
AP_GROUPINFO("SAFETY_MASK", 7, AP_BoardConfig, state.ignore_safety_channels, 0),
245
246
#if HAL_HAVE_IMU_HEATER
247
// @Param: HEAT_TARG
248
// @DisplayName: Board heater temperature target
249
// @Description: Board heater target temperature for boards with controllable heating units. Set to -1 to disable the heater, please reboot after setting to -1.
250
// @Range: -1 80
251
// @Units: degC
252
// @User: Advanced
253
AP_GROUPINFO("HEAT_TARG", 8, AP_BoardConfig, heater.imu_target_temperature, HAL_IMU_TEMP_DEFAULT),
254
#endif
255
256
#if AP_FEATURE_BOARD_DETECT
257
// @Param: TYPE
258
// @DisplayName: Board type
259
// @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
260
// @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Cube/Pixhawk2,5:PixhawkMini,6:Pixhawk2Slim,13:Intel Aero FC,14:Pixhawk Pro,20:AUAV2.1,39:PX4 FMUV6,100:PX4 OLDDRIVERS
261
// @RebootRequired: True
262
// @User: Advanced
263
AP_GROUPINFO("TYPE", 9, AP_BoardConfig, state.board_type, BOARD_TYPE_DEFAULT),
264
#endif
265
266
#if HAL_WITH_IO_MCU
267
// @Param: IO_ENABLE
268
// @DisplayName: Enable IO co-processor
269
// @Description: This allows for the IO co-processor on boards with an IOMCU to be disabled. Setting to 2 will enable the IOMCU but not attempt to update firmware on startup
270
// @Values: 0:Disabled,1:Enabled,2:EnableNoFWUpdate
271
// @RebootRequired: True
272
// @User: Advanced
273
AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1),
274
#endif
275
276
#if AP_RADIO_ENABLED
277
// @Group: RADIO
278
// @Path: ../AP_Radio/AP_Radio.cpp
279
AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio),
280
#endif
281
282
// @Param: SAFETYOPTION
283
// @DisplayName: Options for safety button behavior
284
// @Description: This controls the activation of the safety button. It allows you to control if the safety button can be used for safety enable and/or disable, and whether the button is only active when disarmed
285
// @Bitmask: 0:ActiveForSafetyDisable,1:ActiveForSafetyEnable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms
286
// @User: Standard
287
AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT),
288
289
#if AP_RTC_ENABLED
290
// @Group: RTC
291
// @Path: ../AP_RTC/AP_RTC.cpp
292
AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC),
293
#endif
294
295
#if HAL_HAVE_BOARD_VOLTAGE
296
// @Param: VBUS_MIN
297
// @DisplayName: Autopilot board voltage requirement
298
// @Description: Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
299
// @Units: V
300
// @Range: 4.0 5.5
301
// @Increment: 0.1
302
// @User: Advanced
303
AP_GROUPINFO("VBUS_MIN", 15, AP_BoardConfig, _vbus_min, BOARD_CONFIG_BOARD_VOLTAGE_MIN),
304
305
#endif
306
307
#if HAL_HAVE_SERVO_VOLTAGE
308
// @Param: VSERVO_MIN
309
// @DisplayName: Servo voltage requirement
310
// @Description: Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
311
// @Units: V
312
// @Range: 3.3 12.0
313
// @Increment: 0.1
314
// @User: Advanced
315
AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),
316
#endif
317
318
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
319
// @Param: SD_SLOWDOWN
320
// @DisplayName: microSD slowdown
321
// @Description: This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
322
// @Range: 0 32
323
// @Increment: 1
324
// @User: Advanced
325
AP_GROUPINFO("SD_SLOWDOWN", 17, AP_BoardConfig, _sdcard_slowdown, 0),
326
#endif
327
328
#ifdef HAL_GPIO_PWM_VOLT_PIN
329
// @Param: PWM_VOLT_SEL
330
// @DisplayName: Set PWM Out Voltage
331
// @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxiliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs.
332
// @Values: 0:3.3V,1:5V
333
// @User: Advanced
334
AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),
335
#endif
336
337
// @Param: OPTIONS
338
// @DisplayName: Board options
339
// @Description: Board specific option flags
340
// @Bitmask: 0:Enable hardware watchdog, 1:Disable MAVftp, 2:Enable set of internal parameters, 3:Enable Debug Pins, 4:Unlock flash on reboot, 5:Write protect firmware flash on reboot, 6:Write protect bootloader flash on reboot, 7:Skip board validation, 8:Disable board arming gpio output change on arm/disarm, 9:Use safety pins as profiled
341
// @User: Advanced
342
AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT),
343
344
// @Param: BOOT_DELAY
345
// @DisplayName: Boot delay
346
// @Description: This adds a delay in milliseconds to boot to ensure peripherals initialise fully
347
// @Range: 0 10000
348
// @Units: ms
349
// @User: Advanced
350
AP_GROUPINFO("BOOT_DELAY", 20, AP_BoardConfig, _boot_delay_ms, HAL_DEFAULT_BOOT_DELAY),
351
352
#if HAL_HAVE_IMU_HEATER
353
// @Param: HEAT_P
354
// @DisplayName: Board Heater P gain
355
// @Description: Board Heater P gain
356
// @Range: 1 500
357
// @Increment: 1
358
// @User: Advanced
359
360
// @Param: HEAT_I
361
// @DisplayName: Board Heater I gain
362
// @Description: Board Heater integrator gain
363
// @Range: 0 1
364
// @Increment: 0.1
365
// @User: Advanced
366
367
// @Param: HEAT_IMAX
368
// @DisplayName: Board Heater IMAX
369
// @Description: Board Heater integrator maximum
370
// @Range: 0 100
371
// @Increment: 1
372
// @User: Advanced
373
AP_SUBGROUPINFO(heater.pi_controller, "HEAT_", 21, AP_BoardConfig, AC_PI),
374
#endif
375
376
#ifdef HAL_PIN_ALT_CONFIG
377
// @Param: ALT_CONFIG
378
// @DisplayName: Alternative HW config
379
// @Description: Select an alternative hardware configuration. A value of zero selects the default configuration for this board. Other values are board specific. Please see the documentation for your board for details on any alternative configuration values that may be available.
380
// @Range: 0 10
381
// @Increment: 1
382
// @User: Advanced
383
// @RebootRequired: True
384
AP_GROUPINFO("ALT_CONFIG", 22, AP_BoardConfig, _alt_config, 0),
385
#endif // HAL_PIN_ALT_CONFIG
386
387
#if HAL_HAVE_IMU_HEATER
388
// @Param: HEAT_LOWMGN
389
// @DisplayName: Board heater temp lower margin
390
// @Description: Arming check will fail if temp is lower than this margin below BRD_HEAT_TARG. 0 disables the low temperature check
391
// @Range: 0 20
392
// @Units: degC
393
// @User: Advanced
394
AP_GROUPINFO("HEAT_LOWMGN", 23, AP_BoardConfig, heater.imu_arming_temperature_margin_low, HAL_IMU_TEMP_MARGIN_LOW_DEFAULT),
395
#endif
396
397
#if AP_SDCARD_STORAGE_ENABLED
398
// @Param: SD_MISSION
399
// @DisplayName: SDCard Mission size
400
// @Description: This sets the amount of storage in kilobytes reserved on the microsd card in mission.stg for waypoint storage. Each waypoint uses 15 bytes.
401
// @Range: 0 64
402
// @RebootRequired: True
403
// @User: Advanced
404
AP_GROUPINFO("SD_MISSION", 24, AP_BoardConfig, sdcard_storage.mission_kb, 0),
405
406
// @Param: SD_FENCE
407
// @DisplayName: SDCard Fence size
408
// @Description: This sets the amount of storage in kilobytes reserved on the microsd card in fence.stg for fence storage.
409
// @Range: 0 64
410
// @RebootRequired: True
411
// @User: Advanced
412
AP_GROUPINFO("SD_FENCE", 29, AP_BoardConfig, sdcard_storage.fence_kb, 0),
413
#endif
414
415
// index 25 used by SER5_RTSCTS
416
// index 26 used by SER3_RTSCTS
417
// index 27 used by SER4_RTSCTS
418
419
420
#if HAL_WITH_IO_MCU_DSHOT
421
// @Param: IO_DSHOT
422
// @DisplayName: Load DShot FW on IO
423
// @Description: This loads the DShot firmware on the IO co-processor
424
// @Values: 0:StandardFW,1:DshotFW
425
// @RebootRequired: True
426
// @User: Advanced
427
AP_GROUPINFO("IO_DSHOT", 28, AP_BoardConfig, state.io_dshot, 0),
428
#endif
429
430
// index 30 used by SER6_RTSCTS
431
// index 31 used by SER7_RTSCTS
432
// index 32 used by SER8_RTSCTS
433
434
#if AP_CPU_IDLE_STATS_ENABLED
435
// @Param: IDLE_STATS
436
// @DisplayName: Capture and calculate true CPU load using idle threads
437
// @Description: Capture and calculate true CPU load using idle threads
438
// @Values: 0:Disable,1:Enable
439
// @RebootRequired: True
440
// @User: Advanced
441
AP_GROUPINFO("IDLE_STATS", 33, AP_BoardConfig, state.idle_stats, 0),
442
#endif
443
444
AP_GROUPEND
445
};
446
447
void AP_BoardConfig::init()
448
{
449
// PARAMETER_CONVERSION - Added: APR-2022
450
vehicleSerialNumber.convert_parameter_width(AP_PARAM_INT16);
451
452
board_setup();
453
454
#if AP_RTC_ENABLED
455
AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW);
456
#endif
457
458
if (_boot_delay_ms > 0) {
459
uint16_t delay_ms = uint16_t(_boot_delay_ms.get());
460
if (hal.util->was_watchdog_armed() && delay_ms > 200) {
461
// don't delay a long time on watchdog reset, the pilot
462
// may be able to save the vehicle
463
delay_ms = 200;
464
}
465
hal.scheduler->delay(delay_ms);
466
}
467
468
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(USE_POSIX)
469
uint8_t slowdown = constrain_int16(_sdcard_slowdown.get(), 0, 32);
470
const uint8_t max_slowdown = 8;
471
do {
472
if (AP::FS().retry_mount()) {
473
break;
474
}
475
slowdown++;
476
hal.scheduler->delay(5);
477
} while (slowdown < max_slowdown);
478
if (slowdown < max_slowdown) {
479
_sdcard_slowdown.set(slowdown);
480
} else {
481
printf("SDCard failed to start\n");
482
}
483
#endif
484
}
485
486
// set default value for BRD_SAFETY_MASK
487
void AP_BoardConfig::set_default_safety_ignore_mask(uint32_t mask)
488
{
489
state.ignore_safety_channels.set_default(mask);
490
}
491
492
void AP_BoardConfig::init_safety()
493
{
494
board_init_safety();
495
board_init_debug();
496
}
497
498
/*
499
notify user of a fatal startup error related to available sensors.
500
*/
501
bool AP_BoardConfig::_in_error_loop;
502
503
void AP_BoardConfig::throw_error(const char *err_type, const char *fmt, va_list arg)
504
{
505
_in_error_loop = true;
506
/*
507
to give the user the opportunity to connect to USB we keep
508
repeating the error. The mavlink delay callback is initialised
509
before this, so the user can change parameters (and in
510
particular BRD_TYPE if needed)
511
*/
512
uint32_t last_print_ms = 0;
513
while (true) {
514
uint32_t now = AP_HAL::millis();
515
if (now - last_print_ms >= 5000) {
516
last_print_ms = now;
517
char printfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+2];
518
hal.util->snprintf(printfmt, sizeof(printfmt), "%s: %s\n", err_type, fmt);
519
{
520
va_list arg_copy;
521
va_copy(arg_copy, arg);
522
vprintf(printfmt, arg_copy);
523
va_end(arg_copy);
524
}
525
#if HAL_GCS_ENABLED
526
hal.util->snprintf(printfmt, sizeof(printfmt), "%s: %s", err_type, fmt);
527
{
528
va_list arg_copy;
529
va_copy(arg_copy, arg);
530
gcs().send_textv(MAV_SEVERITY_CRITICAL, printfmt, arg_copy);
531
va_end(arg_copy);
532
}
533
#endif
534
}
535
#if HAL_GCS_ENABLED
536
gcs().update_receive();
537
gcs().update_send();
538
#endif
539
EXPECT_DELAY_MS(10);
540
hal.scheduler->delay(5);
541
}
542
}
543
544
void AP_BoardConfig::allocation_error(const char *fmt, ...)
545
{
546
va_list arg_list;
547
va_start(arg_list, fmt);
548
char newfmt[64] {};
549
snprintf(newfmt, sizeof(newfmt), "Unable to allocate %s", fmt);
550
throw_error("Allocation Error", newfmt, arg_list);
551
va_end(arg_list);
552
}
553
554
void AP_BoardConfig::config_error(const char *fmt, ...)
555
{
556
va_list arg_list;
557
va_start(arg_list, fmt);
558
throw_error("Config Error", fmt, arg_list);
559
va_end(arg_list);
560
}
561
562
/*
563
handle logic for safety state button press. This should be called at
564
10Hz when the button is pressed. The button can either be directly
565
on a pin or on a UAVCAN device
566
This function returns true if the safety state should be toggled
567
*/
568
bool AP_BoardConfig::safety_button_handle_pressed(uint8_t press_count)
569
{
570
if (press_count != 10) {
571
return false;
572
}
573
// get button options
574
uint16_t safety_options = get_safety_button_options();
575
if (!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) &&
576
hal.util->get_soft_armed()) {
577
return false;
578
}
579
AP_HAL::Util::safety_state safety_state = hal.util->safety_switch_state();
580
if (safety_state == AP_HAL::Util::SAFETY_DISARMED &&
581
!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {
582
return false;
583
}
584
if (safety_state == AP_HAL::Util::SAFETY_ARMED &&
585
!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {
586
return false;
587
}
588
return true;
589
}
590
591
namespace AP {
592
AP_BoardConfig *boardConfig(void) {
593
return AP_BoardConfig::get_singleton();
594
}
595
};
596
597