2016-02-17 21:25:16 -04:00
|
|
|
#pragma once
|
2014-01-19 21:57:39 -04:00
|
|
|
|
2023-02-14 05:39:55 -04:00
|
|
|
#include "AP_BoardConfig_config.h"
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2018-04-17 00:53:47 -03:00
|
|
|
#include <AP_RTC/AP_RTC.h>
|
2019-11-01 23:32:12 -03:00
|
|
|
#include <AC_PID/AC_PI.h>
|
2024-05-01 00:23:46 -03:00
|
|
|
#include <AP_Radio/AP_Radio_config.h>
|
2018-01-05 03:00:09 -04:00
|
|
|
|
2024-05-01 00:23:46 -03:00
|
|
|
#if AP_RADIO_ENABLED
|
2018-01-05 04:58:17 -04:00
|
|
|
#include <AP_Radio/AP_Radio.h>
|
|
|
|
#endif
|
|
|
|
|
2016-08-03 01:18:36 -03:00
|
|
|
extern "C" typedef int (*main_fn_t)(int argc, char **);
|
|
|
|
|
2017-04-02 11:56:37 -03:00
|
|
|
class AP_BoardConfig {
|
2014-01-19 21:57:39 -04:00
|
|
|
public:
|
2022-02-21 23:21:35 -04:00
|
|
|
AP_BoardConfig();
|
2017-08-28 21:42:33 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_BoardConfig);
|
2014-01-19 21:57:39 -04:00
|
|
|
|
2018-01-05 04:54:42 -04:00
|
|
|
// singleton support
|
2019-02-10 14:32:23 -04:00
|
|
|
static AP_BoardConfig *get_singleton(void) {
|
|
|
|
return _singleton;
|
2018-01-05 04:54:42 -04:00
|
|
|
}
|
|
|
|
|
2014-01-19 21:57:39 -04:00
|
|
|
void init(void);
|
2017-04-29 21:47:27 -03:00
|
|
|
void init_safety(void);
|
2014-01-19 21:57:39 -04:00
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2017-05-01 23:05:47 -03:00
|
|
|
// notify user of a fatal startup error related to available sensors.
|
2021-09-12 06:02:38 -03:00
|
|
|
static void config_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;
|
|
|
|
|
|
|
|
// notify user of a non-fatal startup error related to allocation failures.
|
|
|
|
static void allocation_error(const char *reason, ...) FMT_PRINTF(1, 2) NORETURN;
|
2017-05-06 06:12:54 -03:00
|
|
|
|
2017-06-06 04:18:15 -03:00
|
|
|
// permit other libraries (in particular, GCS_MAVLink) to detect
|
|
|
|
// that we're never going to boot properly:
|
2021-09-12 06:02:38 -03:00
|
|
|
static bool in_config_error(void) { return _in_error_loop; }
|
2017-06-06 04:18:15 -03:00
|
|
|
|
2017-04-12 15:39:38 -03:00
|
|
|
// valid types for BRD_TYPE: these values need to be in sync with the
|
|
|
|
// values from the param description
|
2016-08-03 04:56:04 -03:00
|
|
|
enum px4_board_type {
|
2018-07-13 07:29:00 -03:00
|
|
|
BOARD_TYPE_UNKNOWN = -1,
|
2016-08-03 04:56:04 -03:00
|
|
|
PX4_BOARD_AUTO = 0,
|
|
|
|
PX4_BOARD_PX4V1 = 1,
|
|
|
|
PX4_BOARD_PIXHAWK = 2,
|
|
|
|
PX4_BOARD_PIXHAWK2 = 3,
|
|
|
|
PX4_BOARD_PIXRACER = 4,
|
|
|
|
PX4_BOARD_PHMINI = 5,
|
|
|
|
PX4_BOARD_PH2SLIM = 6,
|
2017-04-12 15:39:38 -03:00
|
|
|
PX4_BOARD_AEROFC = 13,
|
2017-07-15 02:18:13 -03:00
|
|
|
PX4_BOARD_PIXHAWK_PRO = 14,
|
2017-03-01 03:07:44 -04:00
|
|
|
PX4_BOARD_AUAV21 = 20,
|
2018-01-05 03:00:09 -04:00
|
|
|
PX4_BOARD_PCNC1 = 21,
|
2018-01-11 17:26:14 -04:00
|
|
|
PX4_BOARD_MINDPXV2 = 22,
|
2018-02-14 01:35:40 -04:00
|
|
|
PX4_BOARD_SP01 = 23,
|
2018-05-29 08:43:01 -03:00
|
|
|
PX4_BOARD_FMUV5 = 24,
|
2018-02-03 09:48:37 -04:00
|
|
|
VRX_BOARD_BRAIN51 = 30,
|
|
|
|
VRX_BOARD_BRAIN52 = 32,
|
|
|
|
VRX_BOARD_BRAIN52E = 33,
|
|
|
|
VRX_BOARD_UBRAIN51 = 34,
|
|
|
|
VRX_BOARD_UBRAIN52 = 35,
|
|
|
|
VRX_BOARD_CORE10 = 36,
|
|
|
|
VRX_BOARD_BRAIN54 = 38,
|
2019-02-06 17:09:34 -04:00
|
|
|
PX4_BOARD_FMUV6 = 39,
|
2022-07-18 19:30:56 -03:00
|
|
|
FMUV6_BOARD_HOLYBRO_6X = 40,
|
|
|
|
FMUV6_BOARD_CUAV_6X = 41,
|
2023-10-24 00:52:39 -03:00
|
|
|
FMUV6_BOARD_HOLYBRO_6X_REV6 = 42,
|
2024-01-21 00:36:29 -04:00
|
|
|
FMUV6_BOARD_HOLYBRO_6X_45686 = 43,
|
2020-11-12 20:31:36 -04:00
|
|
|
PX4_BOARD_OLDDRIVERS = 100,
|
2016-08-03 04:56:04 -03:00
|
|
|
};
|
2016-10-20 21:53:34 -03:00
|
|
|
|
|
|
|
// set default value for BRD_SAFETY_MASK
|
2022-05-15 18:30:16 -03:00
|
|
|
void set_default_safety_ignore_mask(uint32_t mask);
|
2016-11-02 21:40:21 -03:00
|
|
|
|
|
|
|
static enum px4_board_type get_board_type(void) {
|
2018-07-13 07:29:00 -03:00
|
|
|
#if AP_FEATURE_BOARD_DETECT
|
2016-11-02 21:40:21 -03:00
|
|
|
return px4_configured_board;
|
2018-07-13 07:29:00 -03:00
|
|
|
#else
|
|
|
|
return BOARD_TYPE_UNKNOWN;
|
2016-11-02 21:40:21 -03:00
|
|
|
#endif
|
2018-07-13 07:29:00 -03:00
|
|
|
}
|
2017-04-02 11:56:37 -03:00
|
|
|
|
2018-05-15 23:52:17 -03:00
|
|
|
// ask if IOMCU is enabled. This is a uint8_t to allow
|
|
|
|
// developer debugging by setting BRD_IO_ENABLE=100 to avoid the
|
|
|
|
// crc check of IO firmware on startup
|
|
|
|
static uint8_t io_enabled(void) {
|
2020-01-17 23:05:54 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
2019-02-10 14:32:23 -04:00
|
|
|
return _singleton?uint8_t(_singleton->state.io_enable.get()):0;
|
2018-01-05 04:54:42 -04:00
|
|
|
#else
|
2018-05-15 23:52:17 -03:00
|
|
|
return 0;
|
2018-01-05 04:54:42 -04:00
|
|
|
#endif
|
|
|
|
}
|
2018-01-06 06:21:46 -04:00
|
|
|
|
2022-08-29 02:23:30 -03:00
|
|
|
static bool io_dshot(void) {
|
2023-06-21 18:44:24 -03:00
|
|
|
#if HAL_WITH_IO_MCU_DSHOT
|
2023-05-24 17:44:24 -03:00
|
|
|
return io_enabled() && _singleton?_singleton->state.io_dshot.get():false;
|
2022-08-29 02:23:30 -03:00
|
|
|
#else
|
|
|
|
return false;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2019-12-29 04:09:27 -04:00
|
|
|
// get alternative config selection
|
|
|
|
uint8_t get_alt_config(void) {
|
|
|
|
return uint8_t(_alt_config.get());
|
|
|
|
}
|
2021-09-23 15:03:43 -03:00
|
|
|
|
2018-04-13 02:56:40 -03:00
|
|
|
enum board_safety_button_option {
|
2019-01-07 20:18:46 -04:00
|
|
|
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF= (1 << 0),
|
|
|
|
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON= (1 << 1),
|
|
|
|
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED= (1 << 2),
|
|
|
|
BOARD_SAFETY_OPTION_SAFETY_ON_DISARM= (1 << 3),
|
2018-04-13 02:56:40 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// return safety button options. Bits are in enum board_safety_button_option
|
2021-02-01 12:26:26 -04:00
|
|
|
uint16_t get_safety_button_options(void) const {
|
2018-04-13 02:56:40 -03:00
|
|
|
return uint16_t(state.safety_option.get());
|
|
|
|
}
|
|
|
|
|
2018-04-14 00:54:23 -03:00
|
|
|
// return the value of BRD_SAFETY_MASK
|
|
|
|
uint16_t get_safety_mask(void) const {
|
2022-05-15 18:30:16 -03:00
|
|
|
return uint32_t(state.ignore_safety_channels.get());
|
2018-04-14 00:54:23 -03:00
|
|
|
}
|
|
|
|
|
2023-07-03 21:26:11 -03:00
|
|
|
uint32_t get_serial_number() const {
|
|
|
|
return (uint32_t)vehicleSerialNumber.get();
|
|
|
|
}
|
|
|
|
|
2018-11-10 17:42:24 -04:00
|
|
|
#if HAL_HAVE_BOARD_VOLTAGE
|
|
|
|
// get minimum board voltage
|
|
|
|
static float get_minimum_board_voltage(void) {
|
2019-02-10 14:32:23 -04:00
|
|
|
return _singleton?_singleton->_vbus_min.get():0;
|
2018-11-10 17:42:24 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_HAVE_SERVO_VOLTAGE
|
|
|
|
// get minimum servo voltage
|
|
|
|
static float get_minimum_servo_voltage(void) {
|
2019-02-10 14:32:23 -04:00
|
|
|
return _singleton?_singleton->_vservo_min.get():0;
|
2018-11-10 17:42:24 -04:00
|
|
|
}
|
|
|
|
#endif
|
2018-12-27 21:06:12 -04:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
static uint8_t get_sdcard_slowdown(void) {
|
2019-02-10 14:32:23 -04:00
|
|
|
return _singleton?_singleton->_sdcard_slowdown.get():0;
|
2018-12-27 21:06:12 -04:00
|
|
|
}
|
|
|
|
#endif
|
2019-04-11 05:25:36 -03:00
|
|
|
|
|
|
|
enum board_options {
|
|
|
|
BOARD_OPTION_WATCHDOG = (1 << 0),
|
2020-11-13 21:54:07 -04:00
|
|
|
DISABLE_FTP = (1<<1),
|
2020-12-03 04:12:14 -04:00
|
|
|
ALLOW_SET_INTERNAL_PARM = (1<<2),
|
2021-12-17 20:08:06 -04:00
|
|
|
BOARD_OPTION_DEBUG_ENABLE = (1<<3),
|
2022-02-18 17:32:17 -04:00
|
|
|
UNLOCK_FLASH = (1<<4),
|
|
|
|
WRITE_PROTECT_FLASH = (1<<5),
|
|
|
|
WRITE_PROTECT_BOOTLOADER = (1<<6),
|
2023-11-16 18:04:20 -04:00
|
|
|
SKIP_BOARD_VALIDATION = (1<<7),
|
|
|
|
DISABLE_ARMING_GPIO = (1<<8)
|
2019-04-11 05:25:36 -03:00
|
|
|
};
|
|
|
|
|
2023-11-16 18:04:20 -04:00
|
|
|
//return true if arming gpio output is disabled
|
|
|
|
static bool arming_gpio_disabled(void) {
|
|
|
|
return _singleton?(_singleton->_options & DISABLE_ARMING_GPIO)!=0:1;
|
|
|
|
}
|
|
|
|
|
|
|
|
#ifndef HAL_ARM_GPIO_POL_INVERT
|
|
|
|
#define HAL_ARM_GPIO_POL_INVERT 0
|
|
|
|
#endif
|
|
|
|
|
2020-11-13 21:54:07 -04:00
|
|
|
// return true if ftp is disabled
|
|
|
|
static bool ftp_disabled(void) {
|
|
|
|
return _singleton?(_singleton->_options & DISABLE_FTP)!=0:1;
|
|
|
|
}
|
|
|
|
|
2019-04-11 05:25:36 -03:00
|
|
|
// return true if watchdog enabled
|
|
|
|
static bool watchdog_enabled(void) {
|
2019-10-20 07:49:24 -03:00
|
|
|
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:HAL_WATCHDOG_ENABLED_DEFAULT;
|
2019-04-11 05:25:36 -03:00
|
|
|
}
|
|
|
|
|
2022-02-18 17:32:17 -04:00
|
|
|
// return true if flash should be unlocked
|
|
|
|
static bool unlock_flash(void) {
|
|
|
|
return _singleton && (_singleton->_options & UNLOCK_FLASH) != 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return true if flash should be write protected
|
|
|
|
static bool protect_flash(void) {
|
|
|
|
return _singleton && (_singleton->_options & WRITE_PROTECT_FLASH) != 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return true if bootloader should be write protected
|
|
|
|
static bool protect_bootloader(void) {
|
|
|
|
return _singleton && (_singleton->_options & WRITE_PROTECT_BOOTLOADER) != 0;
|
|
|
|
}
|
|
|
|
|
2020-12-03 04:12:14 -04:00
|
|
|
// return true if we allow setting of internal parameters (for developers)
|
|
|
|
static bool allow_set_internal_parameters(void) {
|
|
|
|
return _singleton?(_singleton->_options & ALLOW_SET_INTERNAL_PARM)!=0:false;
|
|
|
|
}
|
|
|
|
|
2019-09-02 23:24:18 -03:00
|
|
|
// handle press of safety button. Return true if safety state
|
|
|
|
// should be toggled
|
|
|
|
bool safety_button_handle_pressed(uint8_t press_count);
|
|
|
|
|
2019-11-01 23:32:12 -03:00
|
|
|
#if HAL_HAVE_IMU_HEATER
|
|
|
|
void set_imu_temp(float current_temp_c);
|
2021-02-07 23:43:57 -04:00
|
|
|
|
|
|
|
// heater duty cycle is as a percentage (0 to 100)
|
|
|
|
float get_heater_duty_cycle(void) const {
|
|
|
|
return heater.output;
|
|
|
|
}
|
2021-10-15 18:22:01 -03:00
|
|
|
|
|
|
|
// getters for current temperature and min arming temperature, return false if heater disabled
|
|
|
|
bool get_board_heater_temperature(float &temperature) const;
|
|
|
|
bool get_board_heater_arming_temperature(int8_t &temperature) const;
|
2019-11-01 23:32:12 -03:00
|
|
|
#endif
|
|
|
|
|
2023-02-14 05:39:55 -04:00
|
|
|
#if AP_SDCARD_STORAGE_ENABLED
|
|
|
|
// return number of kb of mission storage to use on microSD
|
|
|
|
static uint16_t get_sdcard_mission_kb(void) {
|
|
|
|
return _singleton? _singleton->sdcard_storage.mission_kb.get() : 0;
|
|
|
|
}
|
2024-02-20 19:59:49 -04:00
|
|
|
|
|
|
|
// return number of kb of fence storage to use on microSD
|
|
|
|
static uint16_t get_sdcard_fence_kb(void) {
|
|
|
|
return _singleton? _singleton->sdcard_storage.fence_kb.get() : 0;
|
|
|
|
}
|
2023-02-14 05:39:55 -04:00
|
|
|
#endif
|
|
|
|
|
2014-01-19 21:57:39 -04:00
|
|
|
private:
|
2019-02-10 14:32:23 -04:00
|
|
|
static AP_BoardConfig *_singleton;
|
2018-01-05 04:54:42 -04:00
|
|
|
|
2022-04-06 03:56:26 -03:00
|
|
|
AP_Int32 vehicleSerialNumber;
|
2019-04-11 05:25:36 -03:00
|
|
|
|
2016-08-02 18:41:24 -03:00
|
|
|
struct {
|
|
|
|
AP_Int8 safety_enable;
|
2018-04-13 02:56:40 -03:00
|
|
|
AP_Int16 safety_option;
|
2016-08-02 18:41:24 -03:00
|
|
|
AP_Int32 ignore_safety_channels;
|
2019-02-25 01:13:46 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
2020-10-02 07:11:03 -03:00
|
|
|
AP_Int8 ser_rtscts[6];
|
2016-08-02 18:41:24 -03:00
|
|
|
AP_Int8 sbus_out_rate;
|
2014-03-31 14:53:16 -03:00
|
|
|
#endif
|
2016-08-03 04:56:04 -03:00
|
|
|
AP_Int8 board_type;
|
2017-03-09 19:43:10 -04:00
|
|
|
AP_Int8 io_enable;
|
2022-08-29 02:23:30 -03:00
|
|
|
AP_Int8 io_dshot;
|
2018-01-05 03:00:09 -04:00
|
|
|
} state;
|
2016-11-02 21:40:21 -03:00
|
|
|
|
2023-02-14 05:39:55 -04:00
|
|
|
#if AP_SDCARD_STORAGE_ENABLED
|
|
|
|
struct {
|
|
|
|
AP_Int16 mission_kb;
|
2024-02-20 19:59:49 -04:00
|
|
|
AP_Int16 fence_kb;
|
2023-02-14 05:39:55 -04:00
|
|
|
} sdcard_storage;
|
|
|
|
#endif
|
|
|
|
|
2018-04-13 20:31:10 -03:00
|
|
|
#if AP_FEATURE_BOARD_DETECT
|
2016-11-02 21:40:21 -03:00
|
|
|
static enum px4_board_type px4_configured_board;
|
2017-04-02 11:56:37 -03:00
|
|
|
|
2018-01-05 03:00:09 -04:00
|
|
|
void board_setup_drivers(void);
|
2016-11-10 00:29:26 -04:00
|
|
|
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
|
2020-09-13 12:23:14 -03:00
|
|
|
bool spi_check_register_inv2(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
|
2017-05-21 22:30:30 -03:00
|
|
|
void validate_board_type(void);
|
2018-01-05 03:00:09 -04:00
|
|
|
void board_autodetect(void);
|
2022-07-18 19:30:56 -03:00
|
|
|
void detect_fmuv6_variant(void);
|
2020-04-27 20:02:33 -03:00
|
|
|
bool check_ms5611(const char* devname);
|
2017-04-02 11:56:37 -03:00
|
|
|
|
2018-01-05 03:00:09 -04:00
|
|
|
#endif // AP_FEATURE_BOARD_DETECT
|
2016-06-15 05:28:18 -03:00
|
|
|
|
2018-04-20 18:31:20 -03:00
|
|
|
void board_init_safety(void);
|
2021-12-17 20:08:06 -04:00
|
|
|
void board_init_debug(void);
|
2018-08-01 20:46:59 -03:00
|
|
|
|
2018-01-07 19:29:53 -04:00
|
|
|
void board_setup_uart(void);
|
|
|
|
void board_setup_sbus(void);
|
|
|
|
void board_setup(void);
|
|
|
|
|
2021-09-12 06:02:38 -03:00
|
|
|
// common method to throw errors
|
|
|
|
static void throw_error(const char *err_str, const char *fmt, va_list arg) NORETURN;
|
|
|
|
|
|
|
|
static bool _in_error_loop;
|
2017-06-06 04:18:15 -03:00
|
|
|
|
2019-11-01 23:32:12 -03:00
|
|
|
#if HAL_HAVE_IMU_HEATER
|
|
|
|
struct {
|
2022-02-21 23:21:35 -04:00
|
|
|
AC_PI pi_controller;
|
2019-11-01 23:32:12 -03:00
|
|
|
AP_Int8 imu_target_temperature;
|
|
|
|
uint32_t last_update_ms;
|
|
|
|
uint16_t count;
|
|
|
|
float sum;
|
|
|
|
float output;
|
|
|
|
uint32_t last_log_ms;
|
2021-10-15 18:22:01 -03:00
|
|
|
float temperature;
|
|
|
|
AP_Int8 imu_arming_temperature_margin_low;
|
2019-11-01 23:32:12 -03:00
|
|
|
} heater;
|
|
|
|
#endif
|
2018-01-05 04:58:17 -04:00
|
|
|
|
2024-05-01 00:23:46 -03:00
|
|
|
#if AP_RADIO_ENABLED
|
2018-01-05 04:58:17 -04:00
|
|
|
// direct attached radio
|
|
|
|
AP_Radio _radio;
|
|
|
|
#endif
|
2023-10-04 04:03:32 -03:00
|
|
|
|
|
|
|
#if AP_RTC_ENABLED
|
2018-04-17 00:53:47 -03:00
|
|
|
// real-time-clock; private because access is via the singleton
|
|
|
|
AP_RTC rtc;
|
2023-10-04 04:03:32 -03:00
|
|
|
#endif
|
2018-11-10 17:42:24 -04:00
|
|
|
|
|
|
|
#if HAL_HAVE_BOARD_VOLTAGE
|
|
|
|
AP_Float _vbus_min;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_HAVE_SERVO_VOLTAGE
|
|
|
|
AP_Float _vservo_min;
|
|
|
|
#endif
|
2018-12-27 21:06:12 -04:00
|
|
|
|
2019-03-29 09:08:35 -03:00
|
|
|
AP_Int8 _pwm_volt_sel;
|
|
|
|
|
2018-12-27 21:06:12 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
AP_Int8 _sdcard_slowdown;
|
|
|
|
#endif
|
2019-04-11 05:25:36 -03:00
|
|
|
|
2019-07-19 03:55:57 -03:00
|
|
|
AP_Int16 _boot_delay_ms;
|
|
|
|
|
2019-04-11 05:25:36 -03:00
|
|
|
AP_Int32 _options;
|
2019-12-29 04:09:27 -04:00
|
|
|
|
|
|
|
AP_Int8 _alt_config;
|
2014-01-19 21:57:39 -04:00
|
|
|
};
|
2019-11-01 23:32:12 -03:00
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_BoardConfig *boardConfig(void);
|
|
|
|
};
|