dRonin  adbada4
dRonin firmware
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
pios_hal.c
Go to the documentation of this file.
1 
12 /*
13  * This program is free software; you can redistribute it and/or modify
14  * it under the terms of the GNU General Public License as published by
15  * the Free Software Foundation; either version 3 of the License, or
16  * (at your option) any later version.
17  *
18  * This program is distributed in the hope that it will be useful, but
19  * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
20  * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
21  * for more details.
22  *
23  * You should have received a copy of the GNU General Public License along
24  * with this program; if not, see <http://www.gnu.org/licenses/>
25  *
26  * Additional note on redistribution: The copyright and license notices above
27  * must be maintained in each individual source file that is a derivative work
28  * of this source file; otherwise redistribution is prohibited.
29  */
30 
31 #include <pios.h>
32 #include <pios_hal.h>
33 #include <openpilot.h>
34 
35 #include <pios_com_priv.h>
36 #include <pios_rcvr_priv.h>
37 
38 #include <pios_modules.h>
39 #include <pios_sys.h>
40 #include <pios_thread.h>
41 
42 #include <dacsettings.h>
43 #include <manualcontrolsettings.h>
44 
45 #if defined(PIOS_INCLUDE_OPENLRS)
46 #include <openlrs.h>
47 #if defined(PIOS_INCLUDE_OPENLRS_RCVR)
48 #include <pios_openlrs_rcvr_priv.h>
49 #endif
50 #endif
51 
52 #if defined(PIOS_INCLUDE_UAVTALKRCVR)
53 #include <pios_uavtalkrcvr_priv.h>
54 #endif
55 
56 #ifdef PIOS_INCLUDE_USART
57 #include <pios_usart_priv.h>
58 #include <pios_sbus_priv.h>
59 #include <pios_dsm_priv.h>
60 #include <pios_ppm_priv.h>
61 #include <pios_pwm_priv.h>
62 #include <pios_hsum_priv.h>
63 
64 #include <pios_usb_cdc_priv.h>
65 #include <pios_usb_hid_priv.h>
66 #endif
67 
68 #include <sanitycheck.h>
69 
70 #ifdef STM32F0XX
71 uintptr_t pios_rcvr_group_map[1];
72 #else
73 uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
74 #endif
75 
76 #if defined(PIOS_INCLUDE_DAC_ANNUNCIATOR)
77 annuncdac_dev_t pios_dac_annunciator_id;
78 #endif
79 
80 uintptr_t pios_com_gps_id;
82 
83 #if defined(PIOS_INCLUDE_MAVLINK)
84 uintptr_t pios_com_mavlink_id;
85 #endif
86 
87 #if defined(PIOS_INCLUDE_MSP_BRIDGE)
88 uintptr_t pios_com_msp_id;
89 #endif
90 
91 #if defined(PIOS_INCLUDE_HOTT)
92 uintptr_t pios_com_hott_id;
93 #endif
94 
95 #if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB)
97 #endif
98 
99 #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY)
100 uintptr_t pios_com_frsky_sport_id;
101 #endif
102 
103 #if defined(PIOS_INCLUDE_LIGHTTELEMETRY)
105 #endif
106 
107 #if defined(PIOS_INCLUDE_STORM32BGC)
108 uintptr_t pios_com_storm32bgc_id;
109 #endif
110 
111 #if defined(PIOS_INCLUDE_TBSVTXCONFIG)
112 uintptr_t pios_com_tbsvtxconfig_id;
113 #endif
114 
115 #if defined(PIOS_INCLUDE_USB_HID) || defined(PIOS_INCLUDE_USB_CDC)
116 uintptr_t pios_com_telem_usb_id;
117 #endif
118 
119 #if defined(PIOS_INCLUDE_USB_CDC)
120 uintptr_t pios_com_vcp_id;
121 #endif
122 
123 #if defined(PIOS_INCLUDE_OPENLRS)
124 uintptr_t pios_com_rf_id;
125 #endif
126 
128 
129 #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
130 #define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
131 uintptr_t pios_com_debug_id;
132 #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
133 
134 #ifndef PIOS_COM_TELEM_RF_RX_BUF_LEN
135 #define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
136 #endif
137 
138 #ifndef PIOS_COM_TELEM_RF_TX_BUF_LEN
139 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
140 #endif
141 
142 #ifndef PIOS_COM_GPS_RX_BUF_LEN
143 #define PIOS_COM_GPS_RX_BUF_LEN 32
144 #endif
145 
146 #ifndef PIOS_COM_GPS_TX_BUF_LEN
147 #define PIOS_COM_GPS_TX_BUF_LEN 16
148 #endif
149 
150 #ifndef PIOS_COM_TELEM_USB_RX_BUF_LEN
151 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 129
152 #endif
153 
154 #ifndef PIOS_COM_TELEM_USB_TX_BUF_LEN
155 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
156 #endif
157 
158 #ifndef PIOS_COM_BRIDGE_RX_BUF_LEN
159 #define PIOS_COM_BRIDGE_RX_BUF_LEN 65
160 #endif
161 
162 #ifndef PIOS_COM_BRIDGE_TX_BUF_LEN
163 #define PIOS_COM_BRIDGE_TX_BUF_LEN 12
164 #endif
165 
166 #ifndef PIOS_COM_MAVLINK_TX_BUF_LEN
167 #define PIOS_COM_MAVLINK_TX_BUF_LEN 128
168 #endif
169 
170 #ifndef PIOS_COM_MSP_TX_BUF_LEN
171 #define PIOS_COM_MSP_TX_BUF_LEN 128
172 #endif
173 
174 #ifndef PIOS_COM_MSP_RX_BUF_LEN
175 #define PIOS_COM_MSP_RX_BUF_LEN 65
176 #endif
177 
178 #ifndef PIOS_COM_HOTT_RX_BUF_LEN
179 #define PIOS_COM_HOTT_RX_BUF_LEN 16
180 #endif
181 
182 #ifndef PIOS_COM_HOTT_TX_BUF_LEN
183 #define PIOS_COM_HOTT_TX_BUF_LEN 16
184 #endif
185 
186 #ifndef PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN
187 #define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128
188 #endif
189 
190 #ifndef PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN
191 #define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 22
192 #endif
193 
194 #ifndef PIOS_COM_FRSKYSPORT_TX_BUF_LEN
195 #define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16
196 #endif
197 
198 #ifndef PIOS_COM_FRSKYSPORT_RX_BUF_LEN
199 #define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16
200 #endif
201 
202 #ifndef PIOS_COM_OPENLOG_TX_BUF_LEN
203 #define PIOS_COM_OPENLOG_TX_BUF_LEN 768
204 #endif
205 
206 #ifndef PIOS_COM_STORM32BGC_RX_BUF_LEN
207 #define PIOS_COM_STORM32BGC_RX_BUF_LEN 32
208 #endif
209 
210 #ifndef PIOS_COM_STORM32BGC_TX_BUF_LEN
211 #define PIOS_COM_STORM32BGC_TX_BUF_LEN 32
212 #endif
213 
214 #ifndef PIOS_COM_TBSVTXCONFIG_TX_BUF_LEN
215 #define PIOS_COM_TBSVTXCONFIG_TX_BUF_LEN 32
216 #endif
217 
218 #ifndef PIOS_COM_TBSVTXCONFIG_RX_BUF_LEN
219 #define PIOS_COM_TBSVTXCONFIG_RX_BUF_LEN 32
220 #endif
221 
222 #ifdef PIOS_INCLUDE_HMC5883
223 #include "pios_hmc5883_priv.h"
224 
225 static const struct pios_hmc5883_cfg external_hmc5883_cfg = {
226  .exti_cfg = NULL,
227  .M_ODR = PIOS_HMC5883_ODR_75,
228  .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
229  .Gain = PIOS_HMC5883_GAIN_1_9,
230  .Mode = PIOS_HMC5883_MODE_SINGLE,
231  .Default_Orientation = PIOS_HMC5883_TOP_0DEG,
232 };
233 #endif
234 
235 #ifdef PIOS_INCLUDE_HMC5983_I2C
236 #include "pios_hmc5983.h"
237 
238 static const struct pios_hmc5983_cfg external_hmc5983_cfg = {
239  .exti_cfg = NULL,
240  .M_ODR = PIOS_HMC5983_ODR_75,
241  .Meas_Conf = PIOS_HMC5983_MEASCONF_NORMAL,
242  .Gain = PIOS_HMC5983_GAIN_1_9,
243  .Mode = PIOS_HMC5983_MODE_SINGLE,
244  .Averaging = PIOS_HMC5983_AVERAGING_1,
245  .Orientation = PIOS_HMC5983_TOP_0DEG,
246 };
247 #endif
248 
249 #ifdef PIOS_INCLUDE_BMP280
250 #include "pios_bmp280_priv.h"
251 
252 static const struct pios_bmp280_cfg external_bmp280_cfg = {
254 };
255 #endif
256 
257 #ifdef PIOS_INCLUDE_MS5611
258 #include "pios_ms5611_priv.h"
259 
260 static const struct pios_ms5611_cfg external_ms5611_cfg = {
262  .temperature_interleaving = 1,
263  .use_0x76_address = false,
264 };
265 #endif
266 
267 #ifdef PIOS_INCLUDE_WS2811
268 #include <pios_ws2811.h>
269 #endif
270 
271 static inline void PIOS_HAL_Err2811(bool on) {
272  (void) on;
273 #ifdef PIOS_INCLUDE_WS2811
274  if (pios_ws2811) {
275  if (on) {
276  PIOS_WS2811_set_all(pios_ws2811, 255, 16, 255);
277  } else {
278  PIOS_WS2811_set_all(pios_ws2811, 0, 32, 0);
279  }
280 
282  }
283 #endif
284 }
285 
291 void PIOS_HAL_CriticalError(uint32_t led_id, enum pios_hal_panic code) {
292 #if defined(PIOS_TOLERATE_MISSING_SENSORS)
293  if (code == PIOS_HAL_PANIC_MAG) {
295  return;
296  }
297 
298  if (code == PIOS_HAL_PANIC_BARO) {
300  return;
301  }
302 #endif
303 
304 #if defined(PIOS_INCLUDE_ANNUNC)
305  for (int cnt = 0; cnt < 3; cnt++) {
306  for (int32_t i = 0; i < code; i++) {
307  PIOS_WDG_Clear();
308  PIOS_ANNUNC_On(led_id);
309  PIOS_HAL_Err2811(true);
310  PIOS_DELAY_WaitmS(175);
311  PIOS_WDG_Clear();
312  PIOS_HAL_Err2811(false);
313  PIOS_ANNUNC_Off(led_id);
314  PIOS_DELAY_WaitmS(175);
315  }
316  PIOS_DELAY_WaitmS(175);
317  PIOS_WDG_Clear();
318  PIOS_DELAY_WaitmS(175);
319  PIOS_WDG_Clear();
320  PIOS_DELAY_WaitmS(175);
321  PIOS_WDG_Clear();
322  }
323 #endif // PIOS_INCLUDE_ANNUNC
324  PIOS_SYS_Reset();
325 }
326 
336 static void PIOS_HAL_SetTarget(uintptr_t *target, uintptr_t value) {
337  if (target) {
338 #ifndef PIOS_NO_ALARMS
339  if (*target) {
340  set_config_error(SYSTEMALARMS_CONFIGERROR_DUPLICATEPORTCFG);
341  }
342 #endif
343 
344  *target = value;
345  }
346 }
347 
348 #ifdef PIOS_INCLUDE_RCVR
349 
355 void PIOS_HAL_SetReceiver(int receiver_type, uintptr_t value) {
356 #ifdef STM32F0XX
357  (void) receiver_type;
359 #else
360  PIOS_HAL_SetTarget(pios_rcvr_group_map + receiver_type, value);
361 #endif
362 }
363 
370 uintptr_t PIOS_HAL_GetReceiver(int receiver_type) {
371  if (receiver_type < 0) {
372  return 0;
373  } else if (receiver_type >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) {
374  return 0;
375  }
376 
377 #ifdef STM32F0XX
378  return pios_rcvr_group_map[0];
379 #else
380  return pios_rcvr_group_map[receiver_type];
381 #endif
382 }
383 #endif // PIOS_INCLUDE_RCVR
384 
385 #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM)
386 
395 void PIOS_HAL_ConfigureCom(const struct pios_usart_cfg *usart_port_cfg,
396  struct pios_usart_params *usart_port_params,
397  size_t rx_buf_len,
398  size_t tx_buf_len,
399  const struct pios_com_driver *com_driver,
400  uintptr_t *com_id)
401 {
402  uintptr_t usart_id;
403  if (PIOS_USART_Init(&usart_id, usart_port_cfg, usart_port_params)) {
404  PIOS_Assert(0);
405  }
406 
407 
408  if (PIOS_COM_Init(com_id, com_driver, usart_id,
409  rx_buf_len, tx_buf_len)) {
410  PIOS_Assert(0);
411  }
412 }
413 #endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */
414 
415 #ifdef PIOS_INCLUDE_DSM
416 
424 static void PIOS_HAL_ConfigureDSM(const struct pios_usart_cfg *usart_dsm_cfg,
425  struct pios_usart_params *usart_port_params,
426  const struct pios_dsm_cfg *dsm_cfg,
427  const struct pios_com_driver *usart_com_driver,
428  HwSharedDSMxModeOptions mode)
429 {
430  uintptr_t usart_dsm_id;
431  if (PIOS_USART_Init(&usart_dsm_id, usart_dsm_cfg, usart_port_params)) {
432  PIOS_Assert(0);
433  }
434 
435  uintptr_t dsm_id;
436  if (PIOS_DSM_Init(&dsm_id, dsm_cfg, usart_com_driver,
437  usart_dsm_id, mode)) {
438  PIOS_Assert(0);
439  }
440 
441  uintptr_t dsm_rcvr_id;
442  if (PIOS_RCVR_Init(&dsm_rcvr_id, &pios_dsm_rcvr_driver, dsm_id)) {
443  PIOS_Assert(0);
444  }
445  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, dsm_rcvr_id);
446 }
447 
448 #endif
449 
450 #ifdef PIOS_INCLUDE_HSUM
451 
458 static void PIOS_HAL_ConfigureHSUM(const struct pios_usart_cfg *usart_hsum_cfg,
459  struct pios_usart_params *usart_port_params,
460  const struct pios_com_driver *usart_com_driver,
461  enum pios_hsum_proto *proto)
462 {
463  uintptr_t usart_hsum_id;
464  if (PIOS_USART_Init(&usart_hsum_id, usart_hsum_cfg, usart_port_params)) {
465  PIOS_Assert(0);
466  }
467 
468  uintptr_t hsum_id;
469  if (PIOS_HSUM_Init(&hsum_id, usart_com_driver,
470  usart_hsum_id, *proto)) {
471  PIOS_Assert(0);
472  }
473 
474  uintptr_t hsum_rcvr_id;
475  if (PIOS_RCVR_Init(&hsum_rcvr_id, &pios_hsum_rcvr_driver, hsum_id)) {
476  PIOS_Assert(0);
477  }
478 
479  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM,
480  hsum_rcvr_id);
481 }
482 #endif
483 
484 #ifdef PIOS_INCLUDE_SRXL
485 
491 static void PIOS_HAL_ConfigureSRXL(const struct pios_usart_cfg *usart_srxl_cfg,
492  struct pios_usart_params *usart_port_params,
493  const struct pios_com_driver *usart_com_driver)
494 {
495  uintptr_t usart_srxl_id;
496  if (PIOS_USART_Init(&usart_srxl_id, usart_srxl_cfg, usart_port_params)) {
497  PIOS_Assert(0);
498  }
499 
500  uintptr_t srxl_id;
501  if (PIOS_SRXL_Init(&srxl_id, usart_com_driver, usart_srxl_id)) {
502  PIOS_Assert(0);
503  }
504 
505  uintptr_t srxl_rcvr_id;
506  if (PIOS_RCVR_Init(&srxl_rcvr_id, &pios_srxl_rcvr_driver, srxl_id)) {
507  PIOS_Assert(0);
508  }
509  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL, srxl_rcvr_id);
510 }
511 
512 #endif // PIOS_INCLUDE_SRXL
513 
514 #ifdef PIOS_INCLUDE_IBUS
515 
522 static void PIOS_HAL_ConfigureIBus(const struct pios_usart_cfg *usart_ibus_cfg,
523  struct pios_usart_params *usart_port_params,
524  const struct pios_com_driver *usart_com_driver)
525 {
526  uintptr_t usart_ibus_id;
527  if (PIOS_USART_Init(&usart_ibus_id, usart_ibus_cfg, usart_port_params))
528  PIOS_Assert(0);
529 
530  uintptr_t ibus_id;
531  if (PIOS_IBus_Init(&ibus_id, usart_com_driver, usart_ibus_id))
532  PIOS_Assert(0);
533 
534  uintptr_t ibus_rcvr_id;
535  if (PIOS_RCVR_Init(&ibus_rcvr_id, &pios_ibus_rcvr_driver, ibus_id))
536  PIOS_Assert(0);
537 
538  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS,
539  ibus_rcvr_id);
540 }
541 #endif
542 
543 #ifdef PIOS_INCLUDE_CROSSFIRE
544 
551 static void PIOS_HAL_ConfigureTbsCrossfire(const struct pios_usart_cfg *usart_crsf_cfg,
552  struct pios_usart_params *usart_port_params,
553  const struct pios_com_driver *usart_com_driver)
554 {
555  uintptr_t usart_crsf_id;
556  if (PIOS_USART_Init(&usart_crsf_id, usart_crsf_cfg, usart_port_params))
557  PIOS_Assert(0);
558 
559  uintptr_t crsf_id;
560  if (PIOS_Crossfire_Init(&crsf_id, usart_com_driver, usart_crsf_id))
561  PIOS_Assert(0);
562 
563  uintptr_t crsf_rcvr_id;
564  if (PIOS_RCVR_Init(&crsf_rcvr_id, &pios_crossfire_rcvr_driver, crsf_id))
565  PIOS_Assert(0);
566 
567  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_TBSCROSSFIRE,
568  crsf_rcvr_id);
569 }
570 #endif // PIOS_INCLUDE_CROSSFIRE
571 
594 #ifdef PIOS_INCLUDE_USART
595 void PIOS_HAL_ConfigurePort(HwSharedPortTypesOptions port_type,
596  const struct pios_usart_cfg *usart_port_cfg,
597  const struct pios_com_driver *com_driver,
598  pios_i2c_t *i2c_id,
599  const struct pios_i2c_adapter_cfg *i2c_cfg,
600  const struct pios_ppm_cfg *ppm_cfg,
601  const struct pios_pwm_cfg *pwm_cfg,
602  uint32_t led_id,
603 /* TODO: future work to factor most of these away */
604  const struct pios_dsm_cfg *dsm_cfg,
605  HwSharedDSMxModeOptions dsm_mode,
606  const struct pios_sbus_cfg *sbus_cfg)
607 {
608  uintptr_t port_driver_id;
609  uintptr_t *target = NULL, *target2 = NULL;
610 
611  struct pios_usart_params usart_port_params;
612 
613  usart_port_params.init.USART_BaudRate = 57600;
614  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
615  usart_port_params.init.USART_Parity = USART_Parity_No;
616  usart_port_params.init.USART_StopBits = USART_StopBits_1;
617  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
618  usart_port_params.init.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
619 
620  usart_port_params.rx_invert = false; // Only used by F3 targets
621  usart_port_params.tx_invert = false; // Only used by F3 targets
622  usart_port_params.rxtx_swap = false; // Only used by F3 targets
623  usart_port_params.single_wire = false; // Only used by F3 targets
624 
625  // If there is a hardware inverter for this port
626  if (sbus_cfg != NULL) {
627  // Enable inverter gpio clock
628  if (sbus_cfg->gpio_clk_func != NULL)
629  (*sbus_cfg->gpio_clk_func)(sbus_cfg->gpio_clk_periph, ENABLE);
630 
631  // Initialize hardware inverter GPIO pin
632  GPIO_Init(sbus_cfg->inv.gpio, (GPIO_InitTypeDef*)&sbus_cfg->inv.init);
633 
634  // Enable Inverter for Sbus
635  if (port_type == HWSHARED_PORTTYPES_SBUS)
636  GPIO_WriteBit(sbus_cfg->inv.gpio, sbus_cfg->inv.init.GPIO_Pin, sbus_cfg->gpio_inv_enable);
637  else
638  GPIO_WriteBit(sbus_cfg->inv.gpio, sbus_cfg->inv.init.GPIO_Pin, sbus_cfg->gpio_inv_disable);
639  }
640 
641  switch (port_type) {
642 
643  case HWSHARED_PORTTYPES_DISABLED:
644  break;
645 
646  case HWSHARED_PORTTYPES_COMBRIDGE:
647  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, com_driver, &port_driver_id);
648  target = &pios_com_bridge_id;
649  //module is enabled by the USB port config rather than here
650  break;
651 
652  case HWSHARED_PORTTYPES_DEBUGCONSOLE:
653 #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
654  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, com_driver, &port_driver_id);
655  target = &pios_com_debug_id;
656 #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
657  break;
658 
659  case HWSHARED_PORTTYPES_DSM:
660 #if defined(PIOS_INCLUDE_DSM)
661  if (dsm_cfg && usart_port_cfg) {
662  usart_port_params.init.USART_BaudRate = 115200;
663  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
664  usart_port_params.init.USART_Parity = USART_Parity_No;
665  usart_port_params.init.USART_StopBits = USART_StopBits_1;
666  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
667  usart_port_params.init.USART_Mode = USART_Mode_Rx;
668 
669  PIOS_HAL_ConfigureDSM(usart_port_cfg, &usart_port_params, dsm_cfg, com_driver, dsm_mode);
670  }
671 #endif /* PIOS_INCLUDE_DSM */
672  break;
673 
674  case HWSHARED_PORTTYPES_FRSKYSENSORHUB:
675 #if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB)
676  usart_port_params.init.USART_BaudRate = 57600;
677  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
678  usart_port_params.init.USART_Parity = USART_Parity_No;
679  usart_port_params.init.USART_StopBits = USART_StopBits_1;
680  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
681  usart_port_params.init.USART_Mode = USART_Mode_Tx;
682 
683  usart_port_params.rx_invert = false;
684  usart_port_params.tx_invert = true;
685  usart_port_params.single_wire = false;
686 
687  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, com_driver, &port_driver_id);
690 #endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */
691  break;
692 
693  case HWSHARED_PORTTYPES_FRSKYSPORTNONINVERTED:
694 #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY)
695  usart_port_params.single_wire = true;
696 
697  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, com_driver, &port_driver_id);
698  target = &pios_com_frsky_sport_id;
700 #endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */
701  break;
702 
703  case HWSHARED_PORTTYPES_FRSKYSPORTTELEMETRY:
704 #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY)
705 #if defined(STM32F30X) || defined(STM32F0XX)
706  // F0 / F3 has internal inverters and can switch rx/tx pins
707  usart_port_params.rx_invert = true;
708  usart_port_params.tx_invert = true;
709  usart_port_params.single_wire = true;
710 #endif // STM32F30X
711 
712 #if defined(USE_STM32F4xx_BRAINFPVRE1)
713  usart_port_params.single_wire = true;
714 #endif // USE_STM32F4xx_BRAINFPVRE1
715 
716  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, com_driver, &port_driver_id);
717  target = &pios_com_frsky_sport_id;
719 #endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */
720  break;
721 
722  case HWSHARED_PORTTYPES_GPS:
723  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, com_driver, &port_driver_id);
724  target = &pios_com_gps_id;
726  break;
727 
728  case HWSHARED_PORTTYPES_HOTTSUMD:
729  case HWSHARED_PORTTYPES_HOTTSUMH:
730 #if defined(PIOS_INCLUDE_HSUM)
731  if (usart_port_cfg) {
732  usart_port_params.init.USART_BaudRate = 115200;
733  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
734  usart_port_params.init.USART_Parity = USART_Parity_No;
735  usart_port_params.init.USART_StopBits = USART_StopBits_1;
736  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
737  usart_port_params.init.USART_Mode = USART_Mode_Rx;
738 
739  enum pios_hsum_proto proto;
740  switch (port_type) {
741  case HWSHARED_PORTTYPES_HOTTSUMD:
742  proto = PIOS_HSUM_PROTO_SUMD;
743  break;
744  case HWSHARED_PORTTYPES_HOTTSUMH:
745  proto = PIOS_HSUM_PROTO_SUMH;
746  break;
747  default:
748  PIOS_Assert(0);
749  break;
750  }
751  PIOS_HAL_ConfigureHSUM(usart_port_cfg, &usart_port_params, com_driver, &proto);
752  }
753 #endif /* PIOS_INCLUDE_HSUM */
754  break;
755 
756  case HWSHARED_PORTTYPES_HOTTTELEMETRY:
757 #if defined(PIOS_INCLUDE_HOTT)
758  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, com_driver, &port_driver_id);
759  target = &pios_com_hott_id;
761 #endif /* PIOS_INCLUDE_HOTT */
762  break;
763 
764  case HWSHARED_PORTTYPES_I2C:
765 #if defined(PIOS_INCLUDE_I2C)
766  if (i2c_id && i2c_cfg) {
767  if (PIOS_I2C_Init(i2c_id, i2c_cfg)) {
768  PIOS_Assert(0);
769  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL);
770  }
771  if (PIOS_I2C_CheckClear(*i2c_id) != 0)
772  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL);
773 
774  if (AlarmsGet(SYSTEMALARMS_ALARM_I2C) == SYSTEMALARMS_ALARM_UNINITIALISED)
775  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_OK);
776  }
777 #endif /* PIOS_INCLUDE_I2C */
778  break;
779 
780  case HWSHARED_PORTTYPES_LIGHTTELEMETRYTX:
781 #if defined(PIOS_INCLUDE_LIGHTTELEMETRY)
782  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, com_driver, &port_driver_id);
783  target = &pios_com_lighttelemetry_id;
785 #endif
786  break;
787 
788  case HWSHARED_PORTTYPES_MAVLINKTX:
789 #if defined(PIOS_INCLUDE_MAVLINK)
790  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, com_driver, &port_driver_id);
791  target = &pios_com_mavlink_id;
793 #endif /* PIOS_INCLUDE_MAVLINK */
794  break;
795 
796  case HWSHARED_PORTTYPES_MAVLINKTX_GPS_RX:
797 #if defined(PIOS_INCLUDE_MAVLINK)
798  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, com_driver, &port_driver_id);
799  target = &pios_com_mavlink_id;
800  target2 = &pios_com_gps_id;
803 #endif /* PIOS_INCLUDE_MAVLINK */
804  break;
805 
806  case HWSHARED_PORTTYPES_MSP:
807 #if defined(PIOS_INCLUDE_MSP_BRIDGE)
808  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, com_driver, &port_driver_id);
809  target = &pios_com_msp_id;
811 #endif
812  break;
813 
814  case HWSHARED_PORTTYPES_OPENLOG:
815 #if defined(PIOS_INCLUDE_OPENLOG)
816  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, 0, PIOS_COM_OPENLOG_TX_BUF_LEN, com_driver, &port_driver_id);
817  target = &pios_com_openlog_logging_id;
818 #endif /* PIOS_INCLUDE_OPENLOG */
819  break;
820 
821  case HWSHARED_PORTTYPES_VTXCONFIGTBSSMARTAUDIO:
822 #if defined(PIOS_INCLUDE_TBSVTXCONFIG)
823  if (usart_port_cfg) {
824  usart_port_params.init.USART_BaudRate = 5000;
825  usart_port_params.init.USART_StopBits = USART_StopBits_2;
826  usart_port_params.init.USART_Parity = USART_Parity_No;
827  usart_port_params.single_wire = true;
828  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_TBSVTXCONFIG_RX_BUF_LEN, PIOS_COM_TBSVTXCONFIG_TX_BUF_LEN, com_driver, &port_driver_id);
829  target = &pios_com_tbsvtxconfig_id;
831  }
832 #endif /* PIOS_INCLUDE_TBSVTXCONFIG */
833  break;
834 
835  case HWSHARED_PORTTYPES_PPM:
836 #if defined(PIOS_INCLUDE_PPM)
837  if (ppm_cfg) {
838  uintptr_t ppm_id;
839  PIOS_PPM_Init(&ppm_id, ppm_cfg);
840 
841  uintptr_t ppm_rcvr_id;
842  if (PIOS_RCVR_Init(&ppm_rcvr_id, &pios_ppm_rcvr_driver, ppm_id)) {
843  PIOS_Assert(0);
844  }
845 
846  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM, ppm_rcvr_id);
847  }
848 #endif /* PIOS_INCLUDE_PPM */
849  break;
850 
851  case HWSHARED_PORTTYPES_PWM:
852 #if defined(PIOS_INCLUDE_PWM)
853  if (pwm_cfg) {
854  uintptr_t pwm_id;
855  PIOS_PWM_Init(&pwm_id, pwm_cfg);
856 
857  uintptr_t pwm_rcvr_id;
858  if (PIOS_RCVR_Init(&pwm_rcvr_id, &pios_pwm_rcvr_driver, pwm_id)) {
859  PIOS_Assert(0);
860  }
861 
862  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM, pwm_rcvr_id);
863  }
864 #endif /* PIOS_INCLUDE_PWM */
865  break;
866 
867  case HWSHARED_PORTTYPES_SBUS:
868  case HWSHARED_PORTTYPES_SBUSNONINVERTED:
869 #if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART)
870  if (usart_port_cfg) {
871  usart_port_params.init.USART_BaudRate = 100000;
872  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
873  usart_port_params.init.USART_Parity = USART_Parity_Even;
874  usart_port_params.init.USART_StopBits = USART_StopBits_2;
875  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
876  usart_port_params.init.USART_Mode = USART_Mode_Rx;
877 
878  if (port_type == HWSHARED_PORTTYPES_SBUS)
879  usart_port_params.rx_invert = true;
880 
881  uintptr_t usart_sbus_id;
882  if (PIOS_USART_Init(&usart_sbus_id, usart_port_cfg, &usart_port_params)) {
883  PIOS_Assert(0);
884  }
885  uintptr_t sbus_id;
886  if (PIOS_SBus_Init(&sbus_id, com_driver, usart_sbus_id)) {
887  PIOS_Assert(0);
888  }
889  uintptr_t sbus_rcvr_id;
890  if (PIOS_RCVR_Init(&sbus_rcvr_id, &pios_sbus_rcvr_driver, sbus_id)) {
891  PIOS_Assert(0);
892  }
893  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS, sbus_rcvr_id);
894  }
895 #endif /* PIOS_INCLUDE_SBUS */
896  break;
897 
898  case HWSHARED_PORTTYPES_STORM32BGC:
899 #if defined(PIOS_INCLUDE_STORM32BGC)
900  usart_port_params.init.USART_BaudRate = 115200;
901 
902  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_STORM32BGC_RX_BUF_LEN, PIOS_COM_STORM32BGC_TX_BUF_LEN, com_driver, &port_driver_id);
903  target = &pios_com_storm32bgc_id;
905 #endif /* PIOS_INCLUDE_STORM32BGC */
906  break;
907 
908  case HWSHARED_PORTTYPES_TELEMETRY:
909  PIOS_HAL_ConfigureCom(usart_port_cfg, &usart_port_params, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, com_driver, &port_driver_id);
910  target = &pios_com_telem_serial_id;
911  break;
912 
913  case HWSHARED_PORTTYPES_SRXL:
914 #if defined(PIOS_INCLUDE_SRXL)
915  if (usart_port_cfg) {
916  usart_port_params.init.USART_BaudRate = 115200;
917  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
918  usart_port_params.init.USART_Parity = USART_Parity_No;
919  usart_port_params.init.USART_StopBits = USART_StopBits_1;
920  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
921  usart_port_params.init.USART_Mode = USART_Mode_Rx;
922 
923  PIOS_HAL_ConfigureSRXL(usart_port_cfg, &usart_port_params, com_driver);
924  }
925 #endif /* PIOS_INCLUDE_SRXL */
926  break;
927 
928  case HWSHARED_PORTTYPES_IBUS:
929 #if defined(PIOS_INCLUDE_IBUS)
930  if (usart_port_cfg) {
931  usart_port_params.init.USART_BaudRate = 115200;
932  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
933  usart_port_params.init.USART_Parity = USART_Parity_No;
934  usart_port_params.init.USART_StopBits = USART_StopBits_1;
935  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
936  usart_port_params.init.USART_Mode = USART_Mode_Rx;
937 
938  PIOS_HAL_ConfigureIBus(usart_port_cfg, &usart_port_params, com_driver);
939  }
940 #endif /* PIOS_INCLUDE_IBUS */
941  break;
942 
943  case HWSHARED_PORTTYPES_TBSCROSSFIRE:
944 #if defined(PIOS_INCLUDE_CROSSFIRE)
945  if (usart_port_cfg) {
946  usart_port_params.init.USART_BaudRate = 420000;
947  usart_port_params.init.USART_WordLength = USART_WordLength_8b;
948  usart_port_params.init.USART_Parity = USART_Parity_No;
949  usart_port_params.init.USART_StopBits = USART_StopBits_1;
950  usart_port_params.init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
951  usart_port_params.init.USART_Mode = USART_Mode_Rx|USART_Mode_Tx;
952 
953  PIOS_HAL_ConfigureTbsCrossfire(usart_port_cfg, &usart_port_params, com_driver);
955  }
956 #endif /* PIOS_INCLUDE_CROSSFIRE */
957  break;
958  } /* port_type */
959 
960  PIOS_HAL_SetTarget(target, port_driver_id);
961  PIOS_HAL_SetTarget(target2, port_driver_id);
962 }
963 #endif /* PIOS_INCLUDE_USART */
964 
965 #if defined(PIOS_INCLUDE_USB_CDC)
966 
972 void PIOS_HAL_ConfigureCDC(HwSharedUSB_VCPPortOptions port_type,
973  uintptr_t usb_id,
974  const struct pios_usb_cdc_cfg *cdc_cfg)
975 {
976  uintptr_t pios_usb_cdc_id;
977 
978  if (port_type != HWSHARED_USB_VCPPORT_DISABLED) {
979  if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, cdc_cfg, usb_id)) {
980  PIOS_Assert(0);
981  }
982  }
983 
984  switch (port_type) {
985  case HWSHARED_USB_VCPPORT_DISABLED:
986  break;
987  case HWSHARED_USB_VCPPORT_USBTELEMETRY:
988  {
992  PIOS_Assert(0);
993  }
994  }
995  break;
996  case HWSHARED_USB_VCPPORT_COMBRIDGE:
997  {
998  if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
1001  PIOS_Assert(0);
1002  }
1004  }
1005  break;
1006  case HWSHARED_USB_VCPPORT_MSP:
1007 #if defined(PIOS_INCLUDE_MSP_BRIDGE)
1008  {
1009  if (PIOS_COM_Init(&pios_com_msp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
1012  PIOS_Assert(0);
1013  }
1015  }
1016 #endif
1017  break;
1018  case HWSHARED_USB_VCPPORT_DEBUGCONSOLE:
1019 #if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
1020  {
1023  pios_usb_cdc_id, 0,
1024  PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
1025  PIOS_Assert(0);
1026  }
1027  }
1028 #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
1029  break;
1030  }
1031 }
1032 #endif
1033 
1034 #if defined(PIOS_INCLUDE_USB_HID)
1035 
1041 void PIOS_HAL_ConfigureHID(HwSharedUSB_HIDPortOptions port_type,
1042  uintptr_t usb_id, const struct pios_usb_hid_cfg *hid_cfg)
1043 {
1044  uintptr_t pios_usb_hid_id;
1045  if (PIOS_USB_HID_Init(&pios_usb_hid_id, hid_cfg, usb_id)) {
1046  PIOS_Assert(0);
1047  }
1048 
1049  switch (port_type) {
1050  case HWSHARED_USB_HIDPORT_DISABLED:
1051  break;
1052  case HWSHARED_USB_HIDPORT_USBTELEMETRY:
1053  {
1055  &pios_usb_hid_com_driver, pios_usb_hid_id,
1058  PIOS_Assert(0);
1059  }
1060  }
1061  break;
1062  }
1063 }
1064 
1065 #endif /* PIOS_INCLUDE_USB_HID */
1066 
1067 #if defined(PIOS_INCLUDE_OPENLRS)
1068 
1075 void PIOS_HAL_ConfigureRFM22B(pios_spi_t spi_dev,
1076  uint8_t board_type, uint8_t board_rev,
1077  HwSharedRfBandOptions rf_band,
1078  HwSharedMaxRfPowerOptions rf_power,
1079  const struct pios_openlrs_cfg *openlrs_cfg,
1080  pios_openlrs_t *handle)
1081 {
1082  OpenLRSInitialize();
1083 
1084  pios_openlrs_t openlrs_id;
1085 
1086  if (PIOS_OpenLRS_Init(&openlrs_id, spi_dev, 0, openlrs_cfg, rf_band,
1087  rf_power)) {
1088  return;
1089  }
1090 
1091  *handle = openlrs_id;
1092 
1093  PIOS_OpenLRS_Start(openlrs_id);
1094 
1095 #if defined(PIOS_INCLUDE_OPENLRS_RCVR)
1096  uintptr_t rfm22brcvr_id;
1097  uintptr_t rfm22brcvr_rcvr_id;
1098 
1099  PIOS_OpenLRS_Rcvr_Init(&rfm22brcvr_id, openlrs_id);
1100 
1101  if (PIOS_RCVR_Init(&rfm22brcvr_rcvr_id, &pios_openlrs_rcvr_driver, rfm22brcvr_id)) {
1102  PIOS_Assert(0);
1103  }
1104 
1105  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS, rfm22brcvr_rcvr_id);
1106 #endif /* PIOS_INCLUDE_OPENLRS_RCVR */
1107 }
1108 #endif /* PIOS_INCLUDE_OPENLRS */
1109 
1110 /* Needs some safety margin over 1000. */
1111 #define BT_COMMAND_DELAY 1100
1112 
1113 #define BT_COMMAND_QDELAY 350
1114 
1115 void PIOS_HAL_ConfigureSerialSpeed(uintptr_t com_id,
1116  HwSharedSpeedBpsOptions speed) {
1117  switch (speed) {
1118  case HWSHARED_SPEEDBPS_1200:
1119  PIOS_COM_ChangeBaud(com_id, 1200);
1120  break;
1121  case HWSHARED_SPEEDBPS_2400:
1122  PIOS_COM_ChangeBaud(com_id, 2400);
1123  break;
1124  case HWSHARED_SPEEDBPS_4800:
1125  PIOS_COM_ChangeBaud(com_id, 4800);
1126  break;
1127  case HWSHARED_SPEEDBPS_9600:
1128  PIOS_COM_ChangeBaud(com_id, 9600);
1129  break;
1130  case HWSHARED_SPEEDBPS_19200:
1131  PIOS_COM_ChangeBaud(com_id, 19200);
1132  break;
1133  case HWSHARED_SPEEDBPS_38400:
1134  PIOS_COM_ChangeBaud(com_id, 38400);
1135  break;
1136  case HWSHARED_SPEEDBPS_57600:
1137  PIOS_COM_ChangeBaud(com_id, 57600);
1138  break;
1139  case HWSHARED_SPEEDBPS_INITHM10:
1140  PIOS_COM_ChangeBaud(com_id, 9600);
1141 
1142  PIOS_COM_SendString(com_id,"AT+BAUD4"); // 115200
1144 
1145  PIOS_COM_ChangeBaud(com_id, 115200);
1146 
1148  PIOS_COM_SendString(com_id,"AT+NAMEdRonin");
1150  PIOS_COM_SendString(com_id,"AT+PASS000000");
1152  PIOS_COM_SendString(com_id,"AT+POWE3");
1154  PIOS_COM_SendString(com_id,"AT+RESET");
1156  break;
1157 
1158  case HWSHARED_SPEEDBPS_INITHC06:
1159  /* Some modules default to 38400, some to 9600.
1160  * Best effort to work with 38400. */
1161 
1162  /* ~4.5 second init time. */
1163  PIOS_COM_ChangeBaud(com_id, 38400);
1164  PIOS_COM_SendString(com_id,"AT+BAUD8"); // 115200
1166 
1167  PIOS_COM_ChangeBaud(com_id, 9600);
1168  PIOS_COM_SendString(com_id,"AT+BAUD8");
1170 
1171  PIOS_COM_ChangeBaud(com_id, 115200);
1172  PIOS_COM_SendString(com_id,"AT+NAMEdRonin");
1174  PIOS_COM_SendString(com_id,"AT+PIN0000");
1176  break;
1177 
1178  case HWSHARED_SPEEDBPS_INITHC05:
1179  /* Some modules default to 38400, some to 9600.
1180  * Best effort to work with 38400. */
1181 
1182  /* Not silence delimited; but usually requires you to
1183  * push a button at magical timing */
1184  PIOS_COM_ChangeBaud(com_id, 38400);
1185  PIOS_COM_SendString(com_id,"AT+UART=115200,0,0\r\n"); // 9600
1187  PIOS_COM_ChangeBaud(com_id, 9600);
1188  PIOS_COM_SendString(com_id,"AT+UART=115200,0,0\r\n"); // 9600
1190 
1191  PIOS_COM_ChangeBaud(com_id, 115200);
1192 
1193  PIOS_COM_SendString(com_id,"AT+NAME=dRonin\r\n");
1195  PIOS_COM_SendString(com_id,"AT+PSWD=0000\r\n");
1197 
1198  break;
1199 
1200  case HWSHARED_SPEEDBPS_115200:
1201  PIOS_COM_ChangeBaud(com_id, 115200);
1202  break;
1203 
1204  case HWSHARED_SPEEDBPS_230400:
1205  PIOS_COM_ChangeBaud(com_id, 230400);
1206  break;
1207  }
1208 }
1209 
1210 
1211 #ifdef PIOS_INCLUDE_I2C
1212 static int PIOS_HAL_ConfigureI2C(pios_i2c_t *id,
1213  const struct pios_i2c_adapter_cfg *cfg) {
1214 #ifndef FLIGHT_POSIX
1215  if (!*id) {
1216  // Not already initialized.
1217  if (PIOS_I2C_Init(id, cfg)) {
1218  PIOS_DEBUG_Assert(0);
1219  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL);
1220 
1221  return -1;
1222  }
1223  }
1224 
1225  if (PIOS_I2C_CheckClear(*id) != 0) {
1226  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL);
1227  return -2;
1228  }
1229 
1230  if (AlarmsGet(SYSTEMALARMS_ALARM_I2C) ==
1231  SYSTEMALARMS_ALARM_UNINITIALISED) {
1232  AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_OK);
1233  }
1234 
1235  PIOS_WDG_Clear();
1236 #endif /* FLIGHT_POSIX */
1237 
1238  return 0;
1239 }
1240 #endif // PIOS_INCLUDE_I2C
1241 
1242 int PIOS_HAL_ConfigureExternalBaro(HwSharedExtBaroOptions baro,
1243  pios_i2c_t *i2c_id,
1244  const struct pios_i2c_adapter_cfg *i2c_cfg)
1245 {
1246 #if !defined(PIOS_INCLUDE_I2C)
1247  return -1;
1248 #else
1249  if (baro == HWSHARED_EXTBARO_NONE) {
1250  return 1;
1251  }
1252 
1253  int ret = PIOS_HAL_ConfigureI2C(i2c_id, i2c_cfg);
1254 
1255  if (ret) goto done;
1256 
1257  switch(baro) {
1258 #if defined(PIOS_INCLUDE_BMP280)
1259  case HWSHARED_EXTBARO_BMP280:
1260  ret = PIOS_BMP280_Init(&external_bmp280_cfg, *i2c_id) ;
1261 
1262  if (ret) goto done;
1263 
1264  ret = PIOS_BMP280_Test();
1265 
1266  if (ret) goto done;
1267 
1268  break;
1269 #endif // PIOS_INCLUDE_BMP280
1270 
1271 #if defined(PIOS_INCLUDE_MS5611)
1272  case HWSHARED_EXTBARO_MS5611:
1273  ret = PIOS_MS5611_Init(&external_ms5611_cfg, *i2c_id);
1274 
1275  if (ret) goto done;
1276 
1277  ret = PIOS_MS5611_Test();
1278 
1279  if (ret) goto done;
1280 
1281  break;
1282 #endif // PIOS_INCLUDE_MS5611
1283 
1284  default:
1285  PIOS_Assert(0); // Should be unreachable
1286  break;
1287  }
1288 
1289 done:
1290  if (ret) {
1292  }
1293 
1294  return ret;
1295 #endif /* PIOS_INCLUDE_I2C */
1296 }
1297 
1298 int PIOS_HAL_ConfigureExternalMag(HwSharedMagOptions mag,
1299  HwSharedMagOrientationOptions orientation,
1300  pios_i2c_t *i2c_id,
1301  const struct pios_i2c_adapter_cfg *i2c_cfg)
1302 {
1303 #if !defined(PIOS_INCLUDE_I2C)
1304  return -1;
1305 #else
1306  if (!HwSharedMagOrientationIsValid(orientation)) {
1307  return -2;
1308  }
1309 
1310  /* internal mag should be handled in pios_board_init */
1311  if (mag == HWSHARED_MAG_NONE || mag == HWSHARED_MAG_INTERNAL) {
1312  return 1;
1313  }
1314 
1315  if (PIOS_HAL_ConfigureI2C(i2c_id, i2c_cfg))
1316  goto mag_fail;
1317 
1318  switch (mag) {
1319 #ifdef PIOS_INCLUDE_HMC5883
1320  case HWSHARED_MAG_EXTERNALHMC5883:
1321  if (PIOS_HMC5883_Init(*i2c_id, &external_hmc5883_cfg))
1322  goto mag_fail;
1323 
1324  if (PIOS_HMC5883_Test())
1325  goto mag_fail;
1326 
1327  /* XXX: Lame. Move driver to HwShared constants.
1328  * Note: drivers rotate around vehicle Z-axis, this rotates around ??
1329  * This is dubious because both the sensor and vehicle Z-axis point down
1330  * in bottom orientation, whereas this is rotating around an upwards vector. */
1331  enum pios_hmc5883_orientation hmc5883_orientation =
1332  (orientation == HWSHARED_MAGORIENTATION_TOP0DEGCW) ? PIOS_HMC5883_TOP_0DEG :
1333  (orientation == HWSHARED_MAGORIENTATION_TOP90DEGCW) ? PIOS_HMC5883_TOP_90DEG :
1334  (orientation == HWSHARED_MAGORIENTATION_TOP180DEGCW) ? PIOS_HMC5883_TOP_180DEG :
1335  (orientation == HWSHARED_MAGORIENTATION_TOP270DEGCW) ? PIOS_HMC5883_TOP_270DEG :
1336  (orientation == HWSHARED_MAGORIENTATION_BOTTOM0DEGCW) ? PIOS_HMC5883_BOTTOM_0DEG :
1337  (orientation == HWSHARED_MAGORIENTATION_BOTTOM90DEGCW) ? PIOS_HMC5883_BOTTOM_270DEG :
1338  (orientation == HWSHARED_MAGORIENTATION_BOTTOM180DEGCW) ? PIOS_HMC5883_BOTTOM_180DEG :
1339  (orientation == HWSHARED_MAGORIENTATION_BOTTOM270DEGCW) ? PIOS_HMC5883_BOTTOM_90DEG :
1340  external_hmc5883_cfg.Default_Orientation;
1341 
1342  PIOS_HMC5883_SetOrientation(hmc5883_orientation);
1343  break;
1344 #endif /* PIOS_INCLUDE_HMC5883 */
1345 
1346 #ifdef PIOS_INCLUDE_HMC5983_I2C
1347  case HWSHARED_MAG_EXTERNALHMC5983:
1348  if (PIOS_HMC5983_I2C_Init(*i2c_id, &external_hmc5983_cfg))
1349  goto mag_fail;
1350 
1351  if (PIOS_HMC5983_Test())
1352  goto mag_fail;
1353 
1354  /* Annoying to do this, but infecting low-level drivers with UAVO deps is yucky
1355  * Note: drivers rotate around vehicle Z-axis, this rotates around ??
1356  * This is dubious because both the sensor and vehicle Z-axis point down
1357  * in bottom orientation, whereas this is rotating around an upwards vector. */
1358  enum pios_hmc5983_orientation hmc5983_orientation =
1359  (orientation == HWSHARED_MAGORIENTATION_TOP0DEGCW) ? PIOS_HMC5983_TOP_0DEG :
1360  (orientation == HWSHARED_MAGORIENTATION_TOP90DEGCW) ? PIOS_HMC5983_TOP_90DEG :
1361  (orientation == HWSHARED_MAGORIENTATION_TOP180DEGCW) ? PIOS_HMC5983_TOP_180DEG :
1362  (orientation == HWSHARED_MAGORIENTATION_TOP270DEGCW) ? PIOS_HMC5983_TOP_270DEG :
1363  (orientation == HWSHARED_MAGORIENTATION_BOTTOM0DEGCW) ? PIOS_HMC5983_BOTTOM_0DEG :
1364  (orientation == HWSHARED_MAGORIENTATION_BOTTOM90DEGCW) ? PIOS_HMC5983_BOTTOM_270DEG :
1365  (orientation == HWSHARED_MAGORIENTATION_BOTTOM180DEGCW) ? PIOS_HMC5983_BOTTOM_180DEG :
1366  (orientation == HWSHARED_MAGORIENTATION_BOTTOM270DEGCW) ? PIOS_HMC5983_BOTTOM_90DEG :
1367  external_hmc5983_cfg.Orientation;
1368 
1369  PIOS_HMC5983_SetOrientation(hmc5983_orientation);
1370  break;
1371 #endif /* PIOS_INCLUDE_HMC5983_I2C */
1372 
1373  default:
1374  PIOS_Assert(0); /* Should be unreachable */
1375  }
1376 
1377  return 0;
1378 
1379 mag_fail:
1381  return -2;
1382 #endif /* PIOS_INCLUDE_I2C */
1383 }
1384 
1385 #ifdef PIOS_INCLUDE_DAC
1386 int PIOS_HAL_ConfigureDAC(dac_dev_t dac)
1387 {
1388  DACSettingsInitialize();
1389 
1390  DACSettingsData settings;
1391 
1392  DACSettingsGet(&settings);
1393 
1394  switch (settings.DACPrimaryUse) {
1395 #ifdef PIOS_INCLUDE_DAC_FSK
1396  case DACSETTINGS_DACPRIMARYUSE_FSK1200:
1398  return -1;
1399  }
1400 
1401  fskdac_dev_t fskdac;
1402 
1403  if (PIOS_FSKDAC_Init(&fskdac, dac)) {
1404  return -1;
1405  }
1406 
1409  (uintptr_t) fskdac, 0,
1411  return -1;
1412  }
1413 
1415  break;
1416 #endif // PIOS_INCLUDE_DAC_FSK
1417 
1418 #ifdef PIOS_INCLUDE_DAC_ANNUNCIATOR
1419  case DACSETTINGS_DACPRIMARYUSE_ANNUNCIATORS:
1420  if (PIOS_ANNUNCDAC_Init(&pios_dac_annunciator_id, dac)) {
1421  return -1;
1422  }
1423  break;
1424 #endif
1425  case DACSETTINGS_DACPRIMARYUSE_DISABLED:
1426  break;
1427  default:
1428  return -1;
1429  }
1430 
1431  return 0;
1432 }
1433 #endif
1434 
1436 {
1437 #if defined(PIOS_INCLUDE_UAVTALKRCVR)
1438  UAVTalkReceiverInitialize();
1439  uintptr_t pios_uavtalk_id;
1440 
1441  if (PIOS_UAVTALKRCVR_Init(&pios_uavtalk_id)) {
1442  PIOS_Assert(0);
1443  }
1444 
1445  uintptr_t pios_uavtalk_rcvr_id;
1446  if (PIOS_RCVR_Init(&pios_uavtalk_rcvr_id,
1448  pios_uavtalk_id)) {
1449  PIOS_Assert(0);
1450  }
1451 
1452  PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_UAVTALK,
1453  pios_uavtalk_rcvr_id);
1454 #endif /* PIOS_INCLUDE_UAVTALKRCVR */
1455 }
#define PIOS_COM_GPS_RX_BUF_LEN
Definition: pios_hal.c:143
#define PIOS_COM_TELEM_USB_RX_BUF_LEN
Definition: pios_hal.c:151
const struct pios_rcvr_driver pios_hsum_rcvr_driver
uint16_t speed
Definition: msp_messages.h:101
#define BT_COMMAND_DELAY
Configure a [flexi/main/rcvr/etc] port.
Definition: pios_hal.c:1111
uintptr_t pios_com_frsky_sport_id
int32_t PIOS_COM_SendString(uintptr_t com_id, const char *str)
#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN
Definition: pios_hal.c:195
const struct pios_exti_cfg * exti_cfg
int32_t PIOS_PWM_Init(uintptr_t *pwm_id, const struct pios_pwm_cfg *cfg)
const struct pios_rcvr_driver pios_pwm_rcvr_driver
void PIOS_HAL_ConfigureCDC(HwSharedUSB_VCPPortOptions port_type, uintptr_t usb_id, const struct pios_usb_cdc_cfg *cdc_cfg)
uintptr_t pios_com_frsky_sensor_hub_id
pios_hmc5983_orientation
Definition: pios_hmc5983.h:105
MS5611 functions header.
struct _msp_pid_item mag
Definition: msp_messages.h:104
void PIOS_HAL_InitUAVTalkReceiver()
Definition: pios_hal.c:1435
static uint8_t board_rev
Definition: firmwareiap.c:71
int32_t PIOS_HMC5883_SetOrientation(enum pios_hmc5883_orientation orientation)
int32_t PIOS_DSM_Init(uintptr_t *dsm_id, const struct pios_dsm_cfg *cfg, const struct pios_com_driver *driver, uintptr_t lower_id, HwSharedDSMxModeOptions mode)
#define PIOS_HMC5883_ODR_75
Main PiOS header to include all the compiled in PiOS options.
pios_hmc5883_orientation
#define PIOS_COM_MSP_TX_BUF_LEN
Definition: pios_hal.c:171
const struct pios_com_driver pios_usb_cdc_com_driver
#define PIOS_COM_MAVLINK_TX_BUF_LEN
Definition: pios_hal.c:167
int PIOS_IBus_Init(uintptr_t *ibus_id, const struct pios_com_driver *driver, uintptr_t uart_id)
Initialises the IBus Rx driver with a serial port.
GPIO_InitTypeDef init
Definition: pios_stm32.h:61
int32_t PIOS_I2C_CheckClear(pios_i2c_t i2c_id)
int32_t PIOS_ANNUNCDAC_Init(annuncdac_dev_t *annuncdac_id, dac_dev_t dac)
Allocate and initialise ANNUNCDAC device.
int32_t PIOS_HMC5883_Test(void)
int PIOS_HAL_ConfigureExternalBaro(HwSharedExtBaroOptions baro, pios_i2c_t *i2c_id, const struct pios_i2c_adapter_cfg *i2c_cfg)
Definition: pios_hal.c:1242
HMC5983 functions header.
COM private definitions.
#define PIOS_COM_STORM32BGC_RX_BUF_LEN
Definition: pios_hal.c:207
void(* gpio_clk_func)(uint32_t periph, FunctionalState state)
int32_t PIOS_SBus_Init(uintptr_t *sbus_id, const struct pios_com_driver *driver, uintptr_t lower_id)
GPIO_TypeDef * gpio
Definition: pios_stm32.h:60
uintptr_t pios_com_tbsvtxconfig_id
uintptr_t pios_com_debug_id
Definition: pios_board.c:76
#define PIOS_DEBUG_Assert(test)
Definition: pios_debug.h:51
#define BT_COMMAND_QDELAY
Definition: pios_hal.c:1113
void PIOS_Modules_Enable(enum pios_modules module)
Definition: pios_modules.c:34
int PIOS_HAL_ConfigureExternalMag(HwSharedMagOptions mag, HwSharedMagOrientationOptions orientation, pios_i2c_t *i2c_id, const struct pios_i2c_adapter_cfg *i2c_cfg)
Definition: pios_hal.c:1298
int32_t PIOS_USB_HID_Init(uintptr_t *usbhid_id, const struct pios_usb_hid_cfg *cfg, uintptr_t lower_id)
const struct pios_rcvr_driver pios_sbus_rcvr_driver
#define PIOS_COM_TELEM_RF_TX_BUF_LEN
Definition: pios_hal.c:139
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
Definition: alarms.c:97
#define PIOS_COM_TBSVTXCONFIG_RX_BUF_LEN
Definition: pios_hal.c:219
Configuration structure for the BMP280 driver.
int32_t PIOS_SRXL_Init(uintptr_t *serial_id, const struct pios_com_driver *driver, uintptr_t lower_id)
Initialize a new SRXL device.
uintptr_t pios_com_gps_id
Definition: pios_hal.c:80
uintptr_t pios_com_hott_id
static void PIOS_HAL_Err2811(bool on)
Definition: pios_hal.c:271
void PIOS_ANNUNC_Off(uint32_t annunc_id)
void set_config_error(SystemAlarmsConfigErrorOptions error_code)
Definition: sanitycheck.c:391
#define PIOS_COM_HOTT_RX_BUF_LEN
Definition: pios_hal.c:179
uintptr_t pios_com_mavlink_id
Utilities to validate a flight configuration.
const struct pios_rcvr_driver pios_openlrs_rcvr_driver
USART_InitTypeDef init
void PIOS_HAL_ConfigureSerialSpeed(uintptr_t com_id, HwSharedSpeedBpsOptions speed)
Definition: pios_hal.c:1115
struct fskdac_dev_s * fskdac_dev_t
Definition: pios_fskdac.h:39
Configuration structure for the MS5611 driver.
#define PIOS_COM_GPS_TX_BUF_LEN
Definition: pios_hal.c:147
USART private definitions.
int32_t PIOS_I2C_Init(pios_i2c_t *i2c_id, const char *path)
void PIOS_WDG_Clear(void)
Clear the watchdog timer.
Definition: pios_wdg.c:147
static struct flyingpicmd_cfg_fa cfg
Definition: main.c:49
uint32_t gpio_clk_periph
Spektrum/JR DSMx satellite receiver private structures.
int32_t PIOS_FSKDAC_Init(fskdac_dev_t *fskdac_id, dac_dev_t dac)
Allocate and initialise FSKDAC device.
enum pios_ms5611_osr oversampling
const struct pios_rcvr_driver pios_ibus_rcvr_driver
enum pios_hmc5983_orientation Orientation
Definition: pios_hmc5983.h:127
uintptr_t pios_com_telem_serial_id
Definition: pios_hal.c:127
#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN
Definition: pios_hal.c:187
const struct pios_com_driver pios_usb_hid_com_driver
#define PIOS_COM_MSP_RX_BUF_LEN
Definition: pios_hal.c:175
#define PIOS_HMC5983_MEASCONF_NORMAL
Definition: pios_hmc5983.h:67
void PIOS_WS2811_set_all(ws2811_dev_t dev, uint8_t r, uint8_t g, uint8_t b)
Sets all LEDs to a color value.
Definition: pios_ws2811.c:219
uintptr_t pios_com_lighttelemetry_id
const struct pios_exti_cfg * exti_cfg
Definition: pios_hmc5983.h:121
#define PIOS_COM_TBSVTXCONFIG_TX_BUF_LEN
Definition: pios_hal.c:215
int32_t PIOS_RCVR_Init(uintptr_t *rcvr_id, const struct pios_rcvr_driver *driver, const uintptr_t lower_id)
struct pios_i2c_adapter * pios_i2c_t
Definition: pios_i2c.h:48
ws2811_dev_t pios_ws2811
Definition: pios_board.c:66
static volatile FlightStatsSettingsData settings
pios_hsum_proto
void PIOS_ANNUNC_On(uint32_t annunc_id)
#define PIOS_HMC5883_GAIN_1_9
#define PIOS_HMC5983_ODR_75
Definition: pios_hmc5983.h:63
#define PIOS_HMC5983_MODE_SINGLE
Definition: pios_hmc5983.h:83
uint8_t i
Definition: msp_messages.h:97
ppm private structures.
#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN
Definition: pios_hal.c:191
struct stm32_gpio inv
#define PIOS_COM_TELEM_RF_RX_BUF_LEN
Definition: pios_hal.c:135
enum channel_mode mode
Definition: pios_servo.c:58
int32_t PIOS_SYS_Reset(void)
#define PIOS_COM_STORM32BGC_TX_BUF_LEN
Definition: pios_hal.c:211
USB COM HID private definitions.
uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]
Definition: pios_hal.c:73
uint16_t value
Definition: storm32bgc.c:155
void PIOS_HAL_ConfigureHID(HwSharedUSB_HIDPortOptions port_type, uintptr_t usb_id, const struct pios_usb_hid_cfg *hid_cfg)
#define PIOS_HMC5983_GAIN_1_9
Definition: pios_hmc5983.h:74
#define PIOS_COM_BRIDGE_TX_BUF_LEN
Definition: pios_hal.c:163
void PIOS_Thread_Sleep(uint32_t time_ms)
Definition: pios_thread.c:229
uintptr_t pios_com_openlog_logging_id
Definition: pios_board.c:49
int32_t PIOS_USART_Init(uintptr_t *usart_id, const struct pios_usart_cfg *cfg, struct pios_usart_params *params)
uintptr_t pios_com_telem_usb_id
Definition: pios_board.c:42
static void PIOS_HAL_SetTarget(uintptr_t *target, uintptr_t value)
Bind a device instance to a role.
Definition: pios_hal.c:336
const struct pios_com_driver pios_fskdac_com_driver
#define PIOS_COM_HOTT_TX_BUF_LEN
Definition: pios_hal.c:183
int32_t PIOS_BMP280_Init(const struct pios_bmp280_cfg *cfg, pios_i2c_t i2c_device)
int32_t PIOS_UAVTALKRCVR_Init(uintptr_t *gcsrcvr_id)
GCS receiver private functions.
int PIOS_Crossfire_Init(uintptr_t *crsf_id, const struct pios_com_driver *driver, uintptr_t uart_id)
Initialises the TBS Crossfire Rx driver with a serial port.
uintptr_t PIOS_HAL_GetReceiver(int receiver_type)
const struct pios_rcvr_driver pios_dsm_rcvr_driver
#define PIOS_HMC5883_MODE_SINGLE
const struct pios_rcvr_driver pios_crossfire_rcvr_driver
int32_t PIOS_COM_Init(uintptr_t *com_id, const struct pios_com_driver *driver, uintptr_t lower_id, uint16_t rx_buffer_len, uint16_t tx_buffer_len)
pios_hal_panic
Definition: pios_hal.h:41
int32_t PIOS_HMC5883_Init(pios_i2c_t i2c_id, const struct pios_hmc5883_cfg *cfg)
#define PIOS_HMC5883_MEASCONF_NORMAL
Futaba S.Bus Private structures.
int32_t PIOS_PPM_Init(uintptr_t *ppm_id, const struct pios_ppm_cfg *cfg)
#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN
Definition: pios_hal.c:199
Includes PiOS and core architecture components.
uint8_t board_type
struct dac_dev_s * dac_dev_t
Definition: pios_dac.h:40
uintptr_t pios_com_storm32bgc_id
void PIOS_WS2811_trigger_update(ws2811_dev_t dev)
Trigger an update of the LED strand.
Definition: pios_ws2811.c:197
#define PIOS_COM_TELEM_USB_TX_BUF_LEN
Definition: pios_hal.c:155
uintptr_t pios_com_msp_id
uintptr_t pios_com_rf_id
int32_t PIOS_MS5611_Init(const struct pios_ms5611_cfg *cfg, pios_i2c_t i2c_device)
enum pios_hmc5883_orientation Default_Orientation
int32_t PIOS_USB_CDC_Init(uintptr_t *usbcdc_id, const struct pios_usb_cdc_cfg *cfg, uintptr_t lower_id)
BitAction gpio_inv_disable
void PIOS_HAL_CriticalError(uint32_t led_id, enum pios_hal_panic code)
Flash a blink code.
Definition: pios_hal.c:291
USB COM CDC private definitions.
BitAction gpio_inv_enable
void PIOS_HAL_SetReceiver(int receiver_type, uintptr_t value)
const struct pios_rcvr_driver pios_ppm_rcvr_driver
uintptr_t pios_com_bridge_id
Definition: pios_hal.c:81
struct annuncdac_dev_s * annuncdac_dev_t
#define PIOS_Assert(test)
Definition: pios_debug.h:52
const struct pios_rcvr_driver pios_uavtalk_rcvr_driver
int32_t PIOS_DELAY_WaitmS(uint32_t mS)
Definition: pios_delay.c:140
const struct pios_rcvr_driver pios_srxl_rcvr_driver
uintptr_t pios_com_vcp_id
#define BMP280_HIGH_RESOLUTION
#define PIOS_COM_OPENLOG_TX_BUF_LEN
Definition: pios_hal.c:203
int32_t PIOS_COM_ChangeBaud(uintptr_t com_id, uint32_t baud)
USART private definitions.
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
Definition: alarms.c:129
void PIOS_SENSORS_SetMissing(enum pios_sensor_type type)
Assert that an optional (non-accel/gyro), but expected sensor is missing.
Definition: pios_sensors.c:191
int32_t PIOS_OpenLRS_Rcvr_Init(uintptr_t *openlrs_rcvr_id, pios_openlrs_t openlrs_id)
int32_t PIOS_HSUM_Init(uintptr_t *hsum_id, const struct pios_com_driver *driver, uintptr_t lower_id, enum pios_hsum_proto proto)
#define PIOS_HMC5983_AVERAGING_1
Definition: pios_hmc5983.h:97
#define PIOS_COM_BRIDGE_RX_BUF_LEN
Definition: pios_hal.c:159