Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BoardConfig/AP_BoardConfig.h
Views: 1798
#pragma once12#include "AP_BoardConfig_config.h"3#include <AP_Common/AP_Common.h>4#include <AP_Param/AP_Param.h>5#include <AP_RTC/AP_RTC.h>6#include <AC_PID/AC_PI.h>7#include <AP_Radio/AP_Radio_config.h>89#if AP_RADIO_ENABLED10#include <AP_Radio/AP_Radio.h>11#endif1213extern "C" typedef int (*main_fn_t)(int argc, char **);1415class AP_BoardConfig {16public:17AP_BoardConfig();1819/* Do not allow copies */20CLASS_NO_COPY(AP_BoardConfig);2122// singleton support23static AP_BoardConfig *get_singleton(void) {24return _singleton;25}2627void init(void);28void init_safety(void);2930static const struct AP_Param::GroupInfo var_info[];3132// notify user of a fatal startup error related to available sensors.33static void config_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;3435// notify user of a non-fatal startup error related to allocation failures.36static void allocation_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;3738// permit other libraries (in particular, GCS_MAVLink) to detect39// that we're never going to boot properly:40static bool in_config_error(void) { return _in_error_loop; }4142// valid types for BRD_TYPE: these values need to be in sync with the43// values from the param description44enum px4_board_type {45BOARD_TYPE_UNKNOWN = -1,46PX4_BOARD_AUTO = 0,47PX4_BOARD_PX4V1 = 1,48PX4_BOARD_PIXHAWK = 2,49PX4_BOARD_PIXHAWK2 = 3,50PX4_BOARD_PIXRACER = 4,51PX4_BOARD_PHMINI = 5,52PX4_BOARD_PH2SLIM = 6,53PX4_BOARD_AEROFC = 13,54PX4_BOARD_PIXHAWK_PRO = 14,55PX4_BOARD_AUAV21 = 20,56PX4_BOARD_PCNC1 = 21,57PX4_BOARD_MINDPXV2 = 22,58PX4_BOARD_SP01 = 23,59PX4_BOARD_FMUV5 = 24,60VRX_BOARD_BRAIN51 = 30,61VRX_BOARD_BRAIN52 = 32,62VRX_BOARD_BRAIN52E = 33,63VRX_BOARD_UBRAIN51 = 34,64VRX_BOARD_UBRAIN52 = 35,65VRX_BOARD_CORE10 = 36,66VRX_BOARD_BRAIN54 = 38,67PX4_BOARD_FMUV6 = 39,68FMUV6_BOARD_HOLYBRO_6X = 40,69FMUV6_BOARD_CUAV_6X = 41,70FMUV6_BOARD_HOLYBRO_6X_REV6 = 42,71FMUV6_BOARD_HOLYBRO_6X_45686 = 43,72PX4_BOARD_OLDDRIVERS = 100,73};7475// set default value for BRD_SAFETY_MASK76void set_default_safety_ignore_mask(uint32_t mask);7778static enum px4_board_type get_board_type(void) {79#if AP_FEATURE_BOARD_DETECT80return px4_configured_board;81#else82return BOARD_TYPE_UNKNOWN;83#endif84}8586// ask if IOMCU is enabled. This is a uint8_t to allow87// developer debugging by setting BRD_IO_ENABLE=100 to avoid the88// crc check of IO firmware on startup89static uint8_t io_enabled(void) {90#if HAL_WITH_IO_MCU91return _singleton?uint8_t(_singleton->state.io_enable.get()):0;92#else93return 0;94#endif95}9697static bool io_dshot(void) {98#if HAL_WITH_IO_MCU_DSHOT99return io_enabled() && _singleton?_singleton->state.io_dshot.get():false;100#else101return false;102#endif103}104105// get alternative config selection106uint8_t get_alt_config(void) {107return uint8_t(_alt_config.get());108}109110enum board_safety_button_option {111BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF= (1 << 0),112BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON= (1 << 1),113BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED= (1 << 2),114BOARD_SAFETY_OPTION_SAFETY_ON_DISARM= (1 << 3),115};116117// return safety button options. Bits are in enum board_safety_button_option118uint16_t get_safety_button_options(void) const {119return uint16_t(state.safety_option.get());120}121122// return the value of BRD_SAFETY_MASK123uint16_t get_safety_mask(void) const {124return uint32_t(state.ignore_safety_channels.get());125}126127uint32_t get_serial_number() const {128return (uint32_t)vehicleSerialNumber.get();129}130131#if HAL_HAVE_BOARD_VOLTAGE132// get minimum board voltage133static float get_minimum_board_voltage(void) {134return _singleton?_singleton->_vbus_min.get():0;135}136#endif137138#if HAL_HAVE_SERVO_VOLTAGE139// get minimum servo voltage140static float get_minimum_servo_voltage(void) {141return _singleton?_singleton->_vservo_min.get():0;142}143#endif144145#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS146static uint8_t get_sdcard_slowdown(void) {147return _singleton?_singleton->_sdcard_slowdown.get():0;148}149#endif150151enum board_options {152BOARD_OPTION_WATCHDOG = (1 << 0),153DISABLE_FTP = (1<<1),154ALLOW_SET_INTERNAL_PARM = (1<<2),155BOARD_OPTION_DEBUG_ENABLE = (1<<3),156UNLOCK_FLASH = (1<<4),157WRITE_PROTECT_FLASH = (1<<5),158WRITE_PROTECT_BOOTLOADER = (1<<6),159SKIP_BOARD_VALIDATION = (1<<7),160DISABLE_ARMING_GPIO = (1<<8),161IO_SAFETY_PINS_AS_PROFILED = (1<<9),162};163164//return true if arming gpio output is disabled165static bool arming_gpio_disabled(void) {166return _singleton?(_singleton->_options & DISABLE_ARMING_GPIO)!=0:1;167}168169#ifndef HAL_ARM_GPIO_POL_INVERT170#define HAL_ARM_GPIO_POL_INVERT 0171#endif172173// return true if ftp is disabled174static bool ftp_disabled(void) {175return _singleton?(_singleton->_options & DISABLE_FTP)!=0:1;176}177178// return true if watchdog enabled179static bool watchdog_enabled(void) {180return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:HAL_WATCHDOG_ENABLED_DEFAULT;181}182183// return true if flash should be unlocked184static bool unlock_flash(void) {185return _singleton && (_singleton->_options & UNLOCK_FLASH) != 0;186}187188// return true if flash should be write protected189static bool protect_flash(void) {190return _singleton && (_singleton->_options & WRITE_PROTECT_FLASH) != 0;191}192193// return true if bootloader should be write protected194static bool protect_bootloader(void) {195return _singleton && (_singleton->_options & WRITE_PROTECT_BOOTLOADER) != 0;196}197198// return true if we allow setting of internal parameters (for developers)199static bool allow_set_internal_parameters(void) {200return _singleton?(_singleton->_options & ALLOW_SET_INTERNAL_PARM)!=0:false;201}202203#if HAL_WITH_IO_MCU204static bool use_safety_as_led(void) {205return _singleton?(_singleton->_options & IO_SAFETY_PINS_AS_PROFILED)!=0:false;206}207#endif208209// handle press of safety button. Return true if safety state210// should be toggled211bool safety_button_handle_pressed(uint8_t press_count);212213#if HAL_HAVE_IMU_HEATER214void set_imu_temp(float current_temp_c);215216// heater duty cycle is as a percentage (0 to 100)217float get_heater_duty_cycle(void) const {218return heater.output;219}220221// getters for current temperature and min arming temperature, return false if heater disabled222bool get_board_heater_temperature(float &temperature) const;223bool get_board_heater_arming_temperature(int8_t &temperature) const;224#endif225226#if AP_SDCARD_STORAGE_ENABLED227// return number of kb of mission storage to use on microSD228static uint16_t get_sdcard_mission_kb(void) {229return _singleton? _singleton->sdcard_storage.mission_kb.get() : 0;230}231232// return number of kb of fence storage to use on microSD233static uint16_t get_sdcard_fence_kb(void) {234return _singleton? _singleton->sdcard_storage.fence_kb.get() : 0;235}236#endif237238private:239static AP_BoardConfig *_singleton;240241AP_Int32 vehicleSerialNumber;242243struct {244AP_Int8 safety_enable;245AP_Int16 safety_option;246AP_Int32 ignore_safety_channels;247#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS248AP_Int8 ser_rtscts[6];249AP_Int8 sbus_out_rate;250#endif251AP_Int8 board_type;252AP_Int8 io_enable;253AP_Int8 io_dshot;254} state;255256#if AP_SDCARD_STORAGE_ENABLED257struct {258AP_Int16 mission_kb;259AP_Int16 fence_kb;260} sdcard_storage;261#endif262263#if AP_FEATURE_BOARD_DETECT264static enum px4_board_type px4_configured_board;265266void board_setup_drivers(void);267bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);268bool spi_check_register_inv2(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);269void validate_board_type(void);270void board_autodetect(void);271void detect_fmuv6_variant(void);272bool check_ms5611(const char* devname);273274#endif // AP_FEATURE_BOARD_DETECT275276void board_init_safety(void);277void board_init_debug(void);278279void board_setup_uart(void);280void board_setup_sbus(void);281void board_setup(void);282283// common method to throw errors284static void throw_error(const char *err_str, const char *fmt, va_list arg) NORETURN;285286static bool _in_error_loop;287288#if HAL_HAVE_IMU_HEATER289struct {290AC_PI pi_controller;291AP_Int8 imu_target_temperature;292uint32_t last_update_ms;293uint16_t count;294float sum;295float output;296uint32_t last_log_ms;297float temperature;298AP_Int8 imu_arming_temperature_margin_low;299} heater;300#endif301302#if AP_RADIO_ENABLED303// direct attached radio304AP_Radio _radio;305#endif306307#if AP_RTC_ENABLED308// real-time-clock; private because access is via the singleton309AP_RTC rtc;310#endif311312#if HAL_HAVE_BOARD_VOLTAGE313AP_Float _vbus_min;314#endif315316#if HAL_HAVE_SERVO_VOLTAGE317AP_Float _vservo_min;318#endif319320AP_Int8 _pwm_volt_sel;321322#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS323AP_Int8 _sdcard_slowdown;324#endif325326AP_Int16 _boot_delay_ms;327328AP_Int32 _options;329330AP_Int8 _alt_config;331};332333namespace AP {334AP_BoardConfig *boardConfig(void);335};336337338