APM:Libraries
AP_BoardConfig.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_Common/AP_Common.h>
5 #include <AP_Param/AP_Param.h>
6 
7 #if defined(HAL_NEEDS_PARAM_HELPER)
9 #endif
10 
11 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || defined(HAL_CHIBIOS_ARCH_FMUV3) || defined(HAL_CHIBIOS_ARCH_FMUV4) || defined(HAL_CHIBIOS_ARCH_MINDPXV2)
12 #define AP_FEATURE_BOARD_DETECT 1
13 #else
14 #define AP_FEATURE_BOARD_DETECT 0
15 #endif
16 
17 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || defined(HAL_CHIBIOS_ARCH_FMUV3) || defined(HAL_CHIBIOS_ARCH_FMUV4) || defined(HAL_CHIBIOS_ARCH_MINDPXV2) || defined(HAL_GPIO_PIN_SAFETY_IN)
18 #define AP_FEATURE_SAFETY_BUTTON 1
19 #else
20 #define AP_FEATURE_SAFETY_BUTTON 0
21 #endif
22 
23 #ifndef AP_FEATURE_RTSCTS
24 #define AP_FEATURE_RTSCTS 0
25 #endif
26 
27 #ifndef AP_FEATURE_RTSCTS
28 #define AP_FEATURE_RTSCTS 0
29 #endif
30 
31 #ifndef AP_FEATURE_SBUS_OUT
32 #define AP_FEATURE_SBUS_OUT 0
33 #endif
34 
35 #if HAL_RCINPUT_WITH_AP_RADIO
36 #include <AP_Radio/AP_Radio.h>
37 #endif
38 
39 extern "C" typedef int (*main_fn_t)(int argc, char **);
40 
42 public:
44  instance = this;
46  };
47 
48  /* Do not allow copies */
49  AP_BoardConfig(const AP_BoardConfig &other) = delete;
50  AP_BoardConfig &operator=(const AP_BoardConfig&) = delete;
51 
52  // singleton support
53  static AP_BoardConfig *get_instance(void) {
54  return instance;
55  }
56 
57  void init(void);
58  void init_safety(void);
59 
60  static const struct AP_Param::GroupInfo var_info[];
61 
62  // notify user of a fatal startup error related to available sensors.
63  static void sensor_config_error(const char *reason);
64 
65  // permit other libraries (in particular, GCS_MAVLink) to detect
66  // that we're never going to boot properly:
67  static bool in_sensor_config_error(void) { return _in_sensor_config_error; }
68 
69 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
70  // public method to start a driver
71  static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
72 #endif
73 
74 #if AP_FEATURE_BOARD_DETECT
75 
76  // valid types for BRD_TYPE: these values need to be in sync with the
77  // values from the param description
79 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
101 #endif
102  };
103 #endif // AP_FEATURE_BOARD_DETECT
104 
105  // set default value for BRD_SAFETY_MASK
106  void set_default_safety_ignore_mask(uint16_t mask);
107 
108 #if AP_FEATURE_BOARD_DETECT
109  static enum px4_board_type get_board_type(void) {
110  return px4_configured_board;
111  }
112 #endif
113 
114  // ask if IOMCU is enabled
115  static bool io_enabled(void) {
116 #if AP_FEATURE_BOARD_DETECT
117  return instance?instance->state.io_enable.get():false;
118 #else
119  return false;
120 #endif
121  }
122 
123  // get number of PWM outputs enabled on FMU
124  static uint8_t get_pwm_count(void) {
125  return instance?instance->pwm_count.get():4;
126  }
127 
128 #if AP_FEATURE_SAFETY_BUTTON
133  };
134 
135  // return safety button options. Bits are in enum board_safety_button_option
136  uint16_t get_safety_button_options(void) {
137  return uint16_t(state.safety_option.get());
138  }
139 #endif
140 
141  // return the value of BRD_SAFETY_MASK
142  uint16_t get_safety_mask(void) const {
143 #if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM)
144  return uint16_t(state.ignore_safety_channels.get());
145 #else
146  return 0;
147 #endif
148  }
149 
150 
151 private:
153 
155  AP_Int8 pwm_count;
156 
157 #if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) || AP_FEATURE_SAFETY_BUTTON
158  struct {
159  AP_Int8 safety_enable;
160  AP_Int16 safety_option;
162 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
163  AP_Int8 ser1_rtscts;
164  AP_Int8 ser2_rtscts;
165  AP_Int8 sbus_out_rate;
166 #endif
167  AP_Int8 board_type;
168  AP_Int8 io_enable;
169  } state;
170 #endif
171 
172 #if AP_FEATURE_BOARD_DETECT
174 
175 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
176  void px4_setup_pwm(void);
177  void px4_setup_safety_mask(void);
178  void px4_tone_alarm(const char *tone_string);
179  void px4_setup_px4io(void);
180  void px4_setup_peripherals(void);
181 #endif
182 
183 
184  void board_setup_drivers(void);
185  bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
186  void validate_board_type(void);
187  void board_autodetect(void);
188 
189 #endif // AP_FEATURE_BOARD_DETECT
190 
191 #if AP_FEATURE_SAFETY_BUTTON
192  void board_init_safety(void);
193  void board_setup_safety_mask(void);
194 #endif
195 
196  void board_setup_uart(void);
197  void board_setup_sbus(void);
198  void board_setup(void);
199 
201 
202  // target temperarure for IMU in Celsius, or -1 to disable
204 
205 #if HAL_RCINPUT_WITH_AP_RADIO
206  // direct attached radio
207  AP_Radio _radio;
208 #endif
209 
210 #if defined(HAL_NEEDS_PARAM_HELPER)
211  // HAL specific parameters
212  AP_Param_Helper param_helper{false};
213 #endif
214 };
static enum px4_board_type get_board_type(void)
void px4_setup_pwm(void)
Definition: px4_drivers.cpp:47
int(* main_fn_t)(int argc, char **)
void board_init_safety(void)
static AP_BoardConfig * get_instance(void)
uint16_t get_safety_mask(void) const
AP_Int8 _imu_target_temperature
AP_Int8 sbus_out_rate
void set_default_safety_ignore_mask(uint16_t mask)
void validate_board_type(void)
void px4_tone_alarm(const char *tone_string)
struct AP_BoardConfig::@14 state
const char * name
Definition: BusTest.cpp:11
void board_setup_uart(void)
static bool io_enabled(void)
static enum px4_board_type px4_configured_board
static uint8_t get_pwm_count(void)
void px4_setup_safety_mask(void)
Definition: px4_drivers.cpp:96
A system for managing and storing variables that are of general interest to the system.
void board_setup_safety_mask(void)
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag=0x80)
void board_autodetect(void)
void board_setup(void)
AP_Int16 safety_option
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments)
AP_Int8 safety_enable
static const struct AP_Param::GroupInfo var_info[]
void board_setup_sbus(void)
void px4_setup_peripherals(void)
Common definitions and utility routines for the ArduPilot libraries.
AP_Int16 vehicleSerialNumber
AP_Int32 ignore_safety_channels
static bool in_sensor_config_error(void)
static bool _in_sensor_config_error
void board_setup_drivers(void)
void px4_setup_px4io(void)
float value
static AP_BoardConfig * instance
uint16_t get_safety_button_options(void)
void init_safety(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP_BoardConfig & operator=(const AP_BoardConfig &)=delete
static void sensor_config_error(const char *reason)