2016-02-17 21:25:16 -04:00
|
|
|
#pragma once
|
2014-01-19 21:57:39 -04:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#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>
|
2018-01-05 03:00:09 -04:00
|
|
|
|
2019-02-06 17:09:34 -04:00
|
|
|
#ifndef AP_FEATURE_BOARD_DETECT
|
2019-02-25 01:13:46 -04:00
|
|
|
#if defined(HAL_CHIBIOS_ARCH_FMUV3) || defined(HAL_CHIBIOS_ARCH_FMUV4) || defined(HAL_CHIBIOS_ARCH_FMUV5) || defined(HAL_CHIBIOS_ARCH_MINDPXV2) || defined(HAL_CHIBIOS_ARCH_FMUV4PRO) || defined(HAL_CHIBIOS_ARCH_BRAINV51) || defined(HAL_CHIBIOS_ARCH_BRAINV52) || defined(HAL_CHIBIOS_ARCH_UBRAINV51) || defined(HAL_CHIBIOS_ARCH_COREV10) || defined(HAL_CHIBIOS_ARCH_BRAINV54)
|
2018-01-05 03:00:09 -04:00
|
|
|
#define AP_FEATURE_BOARD_DETECT 1
|
|
|
|
#else
|
|
|
|
#define AP_FEATURE_BOARD_DETECT 0
|
2018-04-20 18:31:20 -03:00
|
|
|
#endif
|
2019-02-06 17:09:34 -04:00
|
|
|
#endif
|
2018-04-20 18:31:20 -03:00
|
|
|
|
2018-01-19 18:42:24 -04:00
|
|
|
#ifndef AP_FEATURE_RTSCTS
|
|
|
|
#define AP_FEATURE_RTSCTS 0
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef AP_FEATURE_SBUS_OUT
|
2018-01-05 03:00:09 -04:00
|
|
|
#define AP_FEATURE_SBUS_OUT 0
|
|
|
|
#endif
|
2016-06-23 20:48:29 -03:00
|
|
|
|
2018-03-11 11:47:28 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2018-01-05 04:58:17 -04:00
|
|
|
#include <AP_Radio/AP_Radio.h>
|
|
|
|
#endif
|
|
|
|
|
2019-10-20 07:49:24 -03:00
|
|
|
#ifndef HAL_WATCHDOG_ENABLED_DEFAULT
|
|
|
|
#define HAL_WATCHDOG_ENABLED_DEFAULT false
|
|
|
|
#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:
|
2017-12-12 21:06:11 -04:00
|
|
|
AP_BoardConfig() {
|
2019-02-10 14:32:23 -04:00
|
|
|
_singleton = this;
|
2017-12-12 21:06:11 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
};
|
2017-08-28 21:42:33 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
AP_BoardConfig(const AP_BoardConfig &other) = delete;
|
|
|
|
AP_BoardConfig &operator=(const AP_BoardConfig&) = delete;
|
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.
|
2019-11-04 18:55:39 -04:00
|
|
|
static void config_error(const char *reason, ...);
|
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:
|
2019-11-04 18:55:39 -04:00
|
|
|
static bool in_config_error(void) { return _in_sensor_config_error; }
|
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,
|
2016-11-10 22:13:59 -04:00
|
|
|
PX4_BOARD_OLDDRIVERS = 100,
|
2019-02-06 17:09:34 -04:00
|
|
|
PX4_BOARD_FMUV6 = 39,
|
2016-08-03 04:56:04 -03:00
|
|
|
};
|
2016-10-20 21:53:34 -03:00
|
|
|
|
|
|
|
// set default value for BRD_SAFETY_MASK
|
|
|
|
void set_default_safety_ignore_mask(uint16_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
|
|
|
|
|
|
|
// get number of PWM outputs enabled on FMU
|
|
|
|
static uint8_t get_pwm_count(void) {
|
2019-02-10 14:32:23 -04:00
|
|
|
return _singleton?_singleton->pwm_count.get():8;
|
2018-01-06 06:21:46 -04:00
|
|
|
}
|
2018-04-13 02:56:40 -03:00
|
|
|
|
2019-12-29 04:09:27 -04:00
|
|
|
// get alternative config selection
|
|
|
|
uint8_t get_alt_config(void) {
|
|
|
|
return uint8_t(_alt_config.get());
|
|
|
|
}
|
|
|
|
|
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
|
|
|
|
uint16_t get_safety_button_options(void) {
|
|
|
|
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 {
|
|
|
|
#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM)
|
|
|
|
return uint16_t(state.ignore_safety_channels.get());
|
|
|
|
#else
|
|
|
|
return 0;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
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),
|
|
|
|
};
|
|
|
|
|
|
|
|
// 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
|
|
|
}
|
|
|
|
|
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);
|
|
|
|
#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
|
|
|
|
2015-04-29 23:02:27 -03:00
|
|
|
AP_Int16 vehicleSerialNumber;
|
2018-05-25 07:52:41 -03:00
|
|
|
AP_Int8 pwm_count;
|
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
|
2016-08-02 18:41:24 -03:00
|
|
|
AP_Int8 ser1_rtscts;
|
|
|
|
AP_Int8 ser2_rtscts;
|
|
|
|
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;
|
2018-01-05 03:00:09 -04:00
|
|
|
} state;
|
2016-11-02 21:40:21 -03:00
|
|
|
|
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);
|
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);
|
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);
|
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);
|
|
|
|
|
2017-06-06 04:18:15 -03:00
|
|
|
static bool _in_sensor_config_error;
|
|
|
|
|
2019-11-01 23:32:12 -03:00
|
|
|
#if HAL_HAVE_IMU_HEATER
|
|
|
|
struct {
|
|
|
|
AP_Int8 imu_target_temperature;
|
|
|
|
uint32_t last_update_ms;
|
|
|
|
AC_PI pi_controller{200, 0.3, 70};
|
|
|
|
uint16_t count;
|
|
|
|
float sum;
|
|
|
|
float output;
|
|
|
|
uint32_t last_log_ms;
|
|
|
|
} heater;
|
|
|
|
#endif
|
2018-01-05 04:58:17 -04:00
|
|
|
|
2018-03-11 11:47:28 -03:00
|
|
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
2018-01-05 04:58:17 -04:00
|
|
|
// direct attached radio
|
|
|
|
AP_Radio _radio;
|
|
|
|
#endif
|
2018-02-02 16:48:29 -04:00
|
|
|
|
2018-04-17 00:53:47 -03:00
|
|
|
// real-time-clock; private because access is via the singleton
|
|
|
|
AP_RTC rtc;
|
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
|
|
|
#ifdef HAL_GPIO_PWM_VOLT_PIN
|
|
|
|
AP_Int8 _pwm_volt_sel;
|
|
|
|
#endif
|
|
|
|
|
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);
|
|
|
|
};
|