Path: blob/master/libraries/AP_BoardConfig/AP_BoardConfig.cpp
9415 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15* AP_BoardConfig - board specific configuration16*/1718#include "AP_BoardConfig.h"1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>22#include <AP_Math/AP_Math.h>23#include <AP_RTC/AP_RTC.h>24#include <AP_Vehicle/AP_Vehicle_Type.h>25#include <GCS_MAVLink/GCS.h>26#include <AP_Filesystem/AP_Filesystem.h>27#include <GCS_MAVLink/GCS.h>28#include <GCS_MAVLink/GCS_MAVLink.h>29#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>3031#include <stdio.h>3233#ifndef BOARD_TYPE_DEFAULT34#define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO35#endif3637#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS38#ifndef BOARD_SER1_RTSCTS_DEFAULT39# define BOARD_SER1_RTSCTS_DEFAULT 240#endif41#ifndef BOARD_TYPE_DEFAULT42# define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO43#endif44#endif4546#ifndef BOARD_SAFETY_ENABLE_DEFAULT47#if defined(HAL_GPIO_PIN_SAFETY_IN)48// have safety startup enabled if we have a safety pin49# define BOARD_SAFETY_ENABLE_DEFAULT 150#elif defined(HAL_WITH_IO_MCU)51// if we have an IOMCU then enable by default52# define BOARD_SAFETY_ENABLE_DEFAULT HAL_WITH_IO_MCU53#else54# define BOARD_SAFETY_ENABLE_DEFAULT 055#endif56#endif5758#ifndef HAL_IMU_TEMP_DEFAULT59#define HAL_IMU_TEMP_DEFAULT -1 // disabled60#endif6162#ifndef HAL_IMU_TEMP_MARGIN_LOW_DEFAULT63#define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 0 // disabled64#endif6566#ifndef BOARD_SAFETY_OPTION_DEFAULT67# define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)68#endif69#ifndef BOARD_SAFETY_ENABLE70# define BOARD_SAFETY_ENABLE 171#endif7273#ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN74#define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f75#endif7677#ifndef HAL_BRD_OPTIONS_DEFAULT78#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !APM_BUILD_TYPE(APM_BUILD_Replay)79#ifdef HAL_DEBUG_BUILD80#define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG | BOARD_OPTION_DEBUG_ENABLE81#else82#define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG83#endif84#else85#define HAL_BRD_OPTIONS_DEFAULT 086#endif87#endif8889#ifndef HAL_DEFAULT_BOOT_DELAY90#define HAL_DEFAULT_BOOT_DELAY 091#endif9293extern const AP_HAL::HAL& hal;94AP_BoardConfig *AP_BoardConfig::_singleton;9596// constructor97AP_BoardConfig::AP_BoardConfig()98#if HAL_HAVE_IMU_HEATER99// initialise heater PI controller. Note we do this in the cpp file100// for ccache efficiency101: heater{{HAL_IMUHEAT_P_DEFAULT, HAL_IMUHEAT_I_DEFAULT, 70},}102#endif103{104_singleton = this;105AP_Param::setup_object_defaults(this, var_info);106};107108// table of user settable parameters109const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {110111// index 0 was used by PWM_COUNT112113#if AP_FEATURE_RTSCTS114#ifdef HAL_HAVE_RTSCTS_SERIAL1115// @Param: SER1_RTSCTS116// @DisplayName: Serial 1 flow control117// @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.118// @Values: 0:Disabled,1:Enabled,2:Auto,3:RS-485 Driver enable RTS pin119// @RebootRequired: True120// @User: Advanced121AP_GROUPINFO("SER1_RTSCTS", 1, AP_BoardConfig, state.ser_rtscts[1], BOARD_SER1_RTSCTS_DEFAULT),122#endif123124#ifdef HAL_HAVE_RTSCTS_SERIAL2125// @Param: SER2_RTSCTS126// @CopyFieldsFrom: BRD_SER1_RTSCTS127// @DisplayName: Serial 2 flow control128// @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.129AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser_rtscts[2], 2),130#endif131132#ifdef HAL_HAVE_RTSCTS_SERIAL3133// @Param: SER3_RTSCTS134// @CopyFieldsFrom: BRD_SER1_RTSCTS135// @DisplayName: Serial 3 flow control136// @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.137AP_GROUPINFO("SER3_RTSCTS", 26, AP_BoardConfig, state.ser_rtscts[3], 2),138#endif139140#ifdef HAL_HAVE_RTSCTS_SERIAL4141// @Param: SER4_RTSCTS142// @CopyFieldsFrom: BRD_SER1_RTSCTS143// @DisplayName: Serial 4 flow control144// @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.145AP_GROUPINFO("SER4_RTSCTS", 27, AP_BoardConfig, state.ser_rtscts[4], 2),146#endif147148#ifdef HAL_HAVE_RTSCTS_SERIAL5149// @Param: SER5_RTSCTS150// @CopyFieldsFrom: BRD_SER1_RTSCTS151// @DisplayName: Serial 5 flow control152// @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.153AP_GROUPINFO("SER5_RTSCTS", 25, AP_BoardConfig, state.ser_rtscts[5], 2),154#endif155156#ifdef HAL_HAVE_RTSCTS_SERIAL6157// @Param: SER6_RTSCTS158// @CopyFieldsFrom: BRD_SER1_RTSCTS159// @DisplayName: Serial 6 flow control160// @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.161AP_GROUPINFO("SER6_RTSCTS", 30, AP_BoardConfig, state.ser_rtscts[6], 2),162#endif163164#ifdef HAL_HAVE_RTSCTS_SERIAL7165// @Param: SER7_RTSCTS166// @CopyFieldsFrom: BRD_SER1_RTSCTS167// @DisplayName: Serial 7 flow control168// @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.169AP_GROUPINFO("SER7_RTSCTS", 31, AP_BoardConfig, state.ser_rtscts[7], 2),170#endif171172#ifdef HAL_HAVE_RTSCTS_SERIAL8173// @Param: SER8_RTSCTS174// @CopyFieldsFrom: BRD_SER8_RTSCTS175// @DisplayName: Serial 8 flow control176// @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.177AP_GROUPINFO("SER8_RTSCTS", 32, AP_BoardConfig, state.ser_rtscts[8], 2),178#endif179#endif180181// @Param: SAFETY_DEFLT182// @DisplayName: Sets default state of the safety switch183// @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.184// @Values: 0:Disabled,1:Enabled185// @RebootRequired: True186// @User: Standard187AP_GROUPINFO("SAFETY_DEFLT", 3, AP_BoardConfig, state.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT),188189#if AP_FEATURE_SBUS_OUT190// @Param: SBUS_OUT191// @DisplayName: SBUS output rate192// @Description: This sets the SBUS output frame rate in Hz193// @Values: 0:Disabled,1:50Hz,2:75Hz,3:100Hz,4:150Hz,5:200Hz,6:250Hz,7:300Hz194// @RebootRequired: True195// @User: Advanced196AP_GROUPINFO("SBUS_OUT", 4, AP_BoardConfig, state.sbus_out_rate, 0),197#endif198199// @Param: SERIAL_NUM200// @DisplayName: User-defined serial number201// @Description: User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot202// @Range: -8388608 8388607203// @User: Standard204AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0),205206// @Param: SAFETY_MASK207// @DisplayName: Outputs which ignore the safety switch state208// @Description: A bitmask which controls what outputs can move while the safety switch has not been pressed209// @Bitmask: 0:Output1210// @Bitmask: 1:Output2211// @Bitmask: 2:Output3212// @Bitmask: 3:Output4213// @Bitmask: 4:Output5214// @Bitmask: 5:Output6215// @Bitmask: 6:Output7216// @Bitmask: 7:Output8217// @Bitmask: 8:Output9218// @Bitmask: 9:Output10219// @Bitmask: 10:Output11220// @Bitmask: 11:Output12221// @Bitmask: 12:Output13222// @Bitmask: 13:Output14223// @Bitmask: 14:Output15224// @Bitmask: 15:Output16225// @Bitmask: 16:Output17226// @Bitmask: 17:Output18227// @Bitmask: 18:Output19228// @Bitmask: 19:Output20229// @Bitmask: 20:Output21230// @Bitmask: 21:Output22231// @Bitmask: 22:Output23232// @Bitmask: 23:Output24233// @Bitmask: 24:Output25234// @Bitmask: 25:Output26235// @Bitmask: 26:Output27236// @Bitmask: 27:Output28237// @Bitmask: 28:Output29238// @Bitmask: 29:Output30239// @Bitmask: 30:Output31240// @Bitmask: 31:Output32241// @RebootRequired: True242// @User: Advanced243AP_GROUPINFO("SAFETY_MASK", 7, AP_BoardConfig, state.ignore_safety_channels, 0),244245#if HAL_HAVE_IMU_HEATER246// @Param: HEAT_TARG247// @DisplayName: Board heater temperature target248// @Description: Board heater target temperature for boards with controllable heating units. Set to -1 to disable the heater, please reboot after setting to -1.249// @Range: -1 80250// @Units: degC251// @User: Advanced252AP_GROUPINFO("HEAT_TARG", 8, AP_BoardConfig, heater.imu_target_temperature, HAL_IMU_TEMP_DEFAULT),253#endif254255#if AP_FEATURE_BOARD_DETECT256// @Param: TYPE257// @DisplayName: Board type258// @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)259// @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 OLDDRIVERS260// @RebootRequired: True261// @User: Advanced262AP_GROUPINFO("TYPE", 9, AP_BoardConfig, state.board_type, BOARD_TYPE_DEFAULT),263#endif264265#if HAL_WITH_IO_MCU266// @Param: IO_ENABLE267// @DisplayName: Enable IO co-processor268// @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 startup269// @Values: 0:Disabled,1:Enabled,2:EnableNoFWUpdate270// @RebootRequired: True271// @User: Advanced272AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1),273#endif274275#if AP_RADIO_ENABLED276// @Group: RADIO277// @Path: ../AP_Radio/AP_Radio.cpp278AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio),279#endif280281// @Param: SAFETYOPTION282// @DisplayName: Options for safety button behavior283// @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 disarmed284// @Bitmask: 0:ActiveForSafetyDisable,1:ActiveForSafetyEnable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms285// @User: Standard286AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT),287288#if AP_RTC_ENABLED289// @Group: RTC290// @Path: ../AP_RTC/AP_RTC.cpp291AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC),292#endif293294#if HAL_HAVE_BOARD_VOLTAGE295// @Param: VBUS_MIN296// @DisplayName: Autopilot board voltage requirement297// @Description: Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.298// @Units: V299// @Range: 4.0 5.5300// @Increment: 0.1301// @User: Advanced302AP_GROUPINFO("VBUS_MIN", 15, AP_BoardConfig, _vbus_min, BOARD_CONFIG_BOARD_VOLTAGE_MIN),303304#endif305306#if HAL_HAVE_SERVO_VOLTAGE307// @Param: VSERVO_MIN308// @DisplayName: Servo voltage requirement309// @Description: Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.310// @Units: V311// @Range: 3.3 12.0312// @Increment: 0.1313// @User: Advanced314AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),315#endif316317#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS318// @Param: SD_SLOWDOWN319// @DisplayName: microSD slowdown320// @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.321// @Range: 0 32322// @Increment: 1323// @User: Advanced324AP_GROUPINFO("SD_SLOWDOWN", 17, AP_BoardConfig, _sdcard_slowdown, 0),325#endif326327#ifdef HAL_GPIO_PWM_VOLT_PIN328// @Param: PWM_VOLT_SEL329// @DisplayName: Set PWM Out Voltage330// @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.331// @Values: 0:3.3V,1:5V332// @User: Advanced333AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),334#endif335336// @Param: OPTIONS337// @DisplayName: Board options338// @Description: Board specific option flags339// @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 profiled340// @User: Advanced341AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT),342343// @Param: BOOT_DELAY344// @DisplayName: Boot delay345// @Description: This adds a delay in milliseconds to boot to ensure peripherals initialise fully346// @Range: 0 10000347// @Units: ms348// @User: Advanced349AP_GROUPINFO("BOOT_DELAY", 20, AP_BoardConfig, _boot_delay_ms, HAL_DEFAULT_BOOT_DELAY),350351#if HAL_HAVE_IMU_HEATER352// @Param: HEAT_P353// @DisplayName: Board Heater P gain354// @Description: Board Heater P gain355// @Range: 1 500356// @Increment: 1357// @User: Advanced358359// @Param: HEAT_I360// @DisplayName: Board Heater I gain361// @Description: Board Heater integrator gain362// @Range: 0 1363// @Increment: 0.1364// @User: Advanced365366// @Param: HEAT_IMAX367// @DisplayName: Board Heater IMAX368// @Description: Board Heater integrator maximum369// @Range: 0 100370// @Increment: 1371// @User: Advanced372AP_SUBGROUPINFO(heater.pi_controller, "HEAT_", 21, AP_BoardConfig, AC_PI),373#endif374375#ifdef HAL_PIN_ALT_CONFIG376// @Param: ALT_CONFIG377// @DisplayName: Alternative HW config378// @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.379// @Range: 0 10380// @Increment: 1381// @User: Advanced382// @RebootRequired: True383AP_GROUPINFO("ALT_CONFIG", 22, AP_BoardConfig, _alt_config, 0),384#endif // HAL_PIN_ALT_CONFIG385386#if HAL_HAVE_IMU_HEATER387// @Param: HEAT_LOWMGN388// @DisplayName: Board heater temp lower margin389// @Description: Arming check will fail if temp is lower than this margin below BRD_HEAT_TARG. 0 disables the low temperature check390// @Range: 0 20391// @Units: degC392// @User: Advanced393AP_GROUPINFO("HEAT_LOWMGN", 23, AP_BoardConfig, heater.imu_arming_temperature_margin_low, HAL_IMU_TEMP_MARGIN_LOW_DEFAULT),394#endif395396#if AP_SDCARD_STORAGE_ENABLED397// @Param: SD_MISSION398// @DisplayName: SDCard Mission size399// @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.400// @Range: 0 64401// @RebootRequired: True402// @User: Advanced403AP_GROUPINFO("SD_MISSION", 24, AP_BoardConfig, sdcard_storage.mission_kb, 0),404405// @Param: SD_FENCE406// @DisplayName: SDCard Fence size407// @Description: This sets the amount of storage in kilobytes reserved on the microsd card in fence.stg for fence storage.408// @Range: 0 64409// @RebootRequired: True410// @User: Advanced411AP_GROUPINFO("SD_FENCE", 29, AP_BoardConfig, sdcard_storage.fence_kb, 0),412#endif413414// index 25 used by SER5_RTSCTS415// index 26 used by SER3_RTSCTS416// index 27 used by SER4_RTSCTS417418419#if HAL_WITH_IO_MCU_DSHOT420// @Param: IO_DSHOT421// @DisplayName: Load DShot FW on IO422// @Description: This loads the DShot firmware on the IO co-processor423// @Values: 0:StandardFW,1:DshotFW424// @RebootRequired: True425// @User: Advanced426AP_GROUPINFO("IO_DSHOT", 28, AP_BoardConfig, state.io_dshot, 0),427#endif428429// index 30 used by SER6_RTSCTS430// index 31 used by SER7_RTSCTS431// index 32 used by SER8_RTSCTS432433#if AP_CPU_IDLE_STATS_ENABLED434// @Param: IDLE_STATS435// @DisplayName: Capture and calculate true CPU load using idle threads436// @Description: Capture and calculate true CPU load using idle threads437// @Values: 0:Disable,1:Enable438// @RebootRequired: True439// @User: Advanced440AP_GROUPINFO("IDLE_STATS", 33, AP_BoardConfig, state.idle_stats, 0),441#endif442443AP_GROUPEND444};445446void AP_BoardConfig::init()447{448// PARAMETER_CONVERSION - Added: APR-2022449vehicleSerialNumber.convert_parameter_width(AP_PARAM_INT16);450451board_setup();452453#if AP_RTC_ENABLED454AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW);455#endif456457if (_boot_delay_ms > 0) {458uint16_t delay_ms = uint16_t(_boot_delay_ms.get());459if (hal.util->was_watchdog_armed() && delay_ms > 200) {460// don't delay a long time on watchdog reset, the pilot461// may be able to save the vehicle462delay_ms = 200;463}464hal.scheduler->delay(delay_ms);465}466467#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(USE_POSIX)468uint8_t slowdown = constrain_int16(_sdcard_slowdown.get(), 0, 32);469const uint8_t max_slowdown = 8;470do {471if (AP::FS().retry_mount()) {472break;473}474slowdown++;475hal.scheduler->delay(5);476} while (slowdown < max_slowdown);477if (slowdown < max_slowdown) {478_sdcard_slowdown.set(slowdown);479} else {480printf("SDCard failed to start\n");481}482#endif483}484485// set default value for BRD_SAFETY_MASK486void AP_BoardConfig::set_default_safety_ignore_mask(uint32_t mask)487{488state.ignore_safety_channels.set_default(mask);489}490491void AP_BoardConfig::init_safety()492{493board_init_safety();494board_init_debug();495}496497/*498notify user of a fatal startup error related to available sensors.499*/500bool AP_BoardConfig::_in_error_loop;501502void AP_BoardConfig::throw_error(const char *err_type, const char *fmt, va_list arg)503{504_in_error_loop = true;505/*506to give the user the opportunity to connect to USB we keep507repeating the error. The mavlink delay callback is initialised508before this, so the user can change parameters (and in509particular BRD_TYPE if needed)510*/511uint32_t last_print_ms = 0;512while (true) {513uint32_t now = AP_HAL::millis();514if (now - last_print_ms >= 5000) {515last_print_ms = now;516char printfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+2];517hal.util->snprintf(printfmt, sizeof(printfmt), "%s: %s\n", err_type, fmt);518{519va_list arg_copy;520va_copy(arg_copy, arg);521vprintf(printfmt, arg_copy);522va_end(arg_copy);523}524#if HAL_GCS_ENABLED525hal.util->snprintf(printfmt, sizeof(printfmt), "%s: %s", err_type, fmt);526{527va_list arg_copy;528va_copy(arg_copy, arg);529gcs().send_textv(MAV_SEVERITY_CRITICAL, printfmt, arg_copy);530va_end(arg_copy);531}532#endif533}534#if HAL_GCS_ENABLED535gcs().update_receive();536gcs().update_send();537#endif538EXPECT_DELAY_MS(10);539hal.scheduler->delay(5);540}541}542543void AP_BoardConfig::allocation_error(const char *fmt, ...)544{545va_list arg_list;546va_start(arg_list, fmt);547char newfmt[64] {};548snprintf(newfmt, sizeof(newfmt), "Unable to allocate %s", fmt);549throw_error("Allocation Error", newfmt, arg_list);550va_end(arg_list);551}552553void AP_BoardConfig::config_error(const char *fmt, ...)554{555va_list arg_list;556va_start(arg_list, fmt);557throw_error("Config Error", fmt, arg_list);558va_end(arg_list);559}560561/*562handle logic for safety state button press. This should be called at56310Hz when the button is pressed. The button can either be directly564on a pin or on a UAVCAN device565This function returns true if the safety state should be toggled566*/567bool AP_BoardConfig::safety_button_handle_pressed(uint8_t press_count)568{569if (press_count != 10) {570return false;571}572// get button options573uint16_t safety_options = get_safety_button_options();574if (!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) &&575hal.util->get_soft_armed()) {576return false;577}578AP_HAL::Util::safety_state safety_state = hal.util->safety_switch_state();579if (safety_state == AP_HAL::Util::SAFETY_DISARMED &&580!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {581return false;582}583if (safety_state == AP_HAL::Util::SAFETY_ARMED &&584!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {585return false;586}587return true;588}589590namespace AP {591AP_BoardConfig *boardConfig(void) {592return AP_BoardConfig::get_singleton();593}594};595596597