void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); const struct pios_board_info * bdinfo = &pios_board_info_blob; #if defined(PIOS_INCLUDE_LED) const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); PIOS_Assert(led_cfg); PIOS_LED_Init(led_cfg); #endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_FLASH) /* Inititialize all flash drivers */ if (PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg) != 0) panic(1); /* Register the partition table */ const struct pios_flash_partition * flash_partition_table; uint32_t num_partitions; flash_partition_table = PIOS_BOARD_HW_DEFS_GetPartitionTable(bdinfo->board_rev, &num_partitions); PIOS_FLASH_register_partition_table(flash_partition_table, num_partitions); /* Mount all filesystems */ if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS) != 0) panic(1); #if defined(PIOS_INCLUDE_EXTERNAL_FLASH_WAYPOINTS) /* Use external flash chip to store waypoints */ if (PIOS_FLASHFS_Logfs_Init(&pios_waypoints_settings_fs_id, &flashfs_external_waypoints_cfg, FLASH_PARTITION_LABEL_WAYPOINTS) != 0) panic(1); #endif /* PIOS_INCLUDE_EXTERNAL_FLASH_WAYPOINTS */ #endif /* PIOS_INCLUDE_FLASH */ /* Initialize the task monitor library */ TaskMonitorInitialize(); /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); /* Initialize the alarms library */ AlarmsInitialize(); HwFlyingF4Initialize(); ModuleSettingsInitialize(); #if defined(PIOS_INCLUDE_RTC) /* Initialize the real-time clock and its associated tick */ PIOS_RTC_Init(&pios_rtc_main_cfg); #endif #ifndef ERASE_FLASH /* Initialize watchdog as early as possible to catch faults during init * but do it only if there is no debugger connected */ if ((CoreDebug->DHCSR & CoreDebug_DHCSR_C_DEBUGEN_Msk) == 0) { PIOS_WDG_Init(); } #endif /* Set up pulse timers */ //inputs PIOS_TIM_InitClock(&tim_2_cfg); PIOS_TIM_InitClock(&tim_4_cfg); PIOS_TIM_InitClock(&tim_8_cfg); PIOS_TIM_InitClock(&tim_9_cfg); //outputs PIOS_TIM_InitClock(&tim_1_cfg); PIOS_TIM_InitClock(&tim_3_cfg); /* IAP System Setup */ PIOS_IAP_Init(); uint16_t boot_count = PIOS_IAP_ReadBootCount(); if (boot_count < 3) { PIOS_IAP_WriteBootCount(++boot_count); AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); } else { /* Too many failed boot attempts, force hw config to defaults */ HwFlyingF4SetDefaults(HwFlyingF4Handle(), 0); ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); } #if defined(PIOS_INCLUDE_USB) /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); /* Flags to determine if various USB interfaces are advertised */ bool usb_hid_present = false; bool usb_cdc_present = false; #if defined(PIOS_INCLUDE_USB_CDC) if (PIOS_USB_DESC_HID_CDC_Init()) { PIOS_Assert(0); } usb_hid_present = true; usb_cdc_present = true; #else if (PIOS_USB_DESC_HID_ONLY_Init()) { PIOS_Assert(0); } usb_hid_present = true; #endif uintptr_t pios_usb_id; PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_USB_CDC) uint8_t hw_usb_vcpport; /* Configure the USB VCP port */ HwFlyingF4USB_VCPPortGet(&hw_usb_vcpport); if (!usb_cdc_present) { /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ hw_usb_vcpport = HWFLYINGF4_USB_VCPPORT_DISABLED; } uintptr_t pios_usb_cdc_id; if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { PIOS_Assert(0); } switch (hw_usb_vcpport) { case HWFLYINGF4_USB_VCPPORT_DISABLED: break; case HWFLYINGF4_USB_VCPPORT_USBTELEMETRY: #if defined(PIOS_INCLUDE_COM) { uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; case HWFLYINGF4_USB_VCPPORT_COMBRIDGE: #if defined(PIOS_INCLUDE_COM) { uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; case HWFLYINGF4_USB_VCPPORT_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) { uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, NULL, 0, tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ #endif /* PIOS_INCLUDE_COM */ break; case HWFLYINGF4_USB_VCPPORT_PICOC: #if defined(PIOS_INCLUDE_COM) { uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; } #endif /* PIOS_INCLUDE_USB_CDC */ #if defined(PIOS_INCLUDE_USB_HID) /* Configure the usb HID port */ uint8_t hw_usb_hidport; HwFlyingF4USB_HIDPortGet(&hw_usb_hidport); if (!usb_hid_present) { /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ hw_usb_hidport = HWFLYINGF4_USB_HIDPORT_DISABLED; } uintptr_t pios_usb_hid_id; if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { PIOS_Assert(0); } switch (hw_usb_hidport) { case HWFLYINGF4_USB_HIDPORT_DISABLED: break; case HWFLYINGF4_USB_HIDPORT_USBTELEMETRY: #if defined(PIOS_INCLUDE_COM) { uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; } #endif /* PIOS_INCLUDE_USB_HID */ if (usb_hid_present || usb_cdc_present) { PIOS_USBHOOK_Activate(); } #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ uint8_t hw_DSMxBind; HwFlyingF4DSMxBindGet(&hw_DSMxBind); /* init sensor queue registration */ PIOS_SENSORS_Init(); /* UART1 Port */ uint8_t hw_uart1; HwFlyingF4Uart1Get(&hw_uart1); switch (hw_uart1) { case HWFLYINGF4_UART1_DISABLED: break; case HWFLYINGF4_UART1_GPS: #if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); #endif break; case HWFLYINGF4_UART1_SBUS: //hardware signal inverter required #if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) { uintptr_t pios_usart_sbus_id; if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart1_sbus_cfg)) { PIOS_Assert(0); } uintptr_t pios_sbus_id; if (PIOS_SBus_Init(&pios_sbus_id, &pios_usart1_sbus_aux_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { PIOS_Assert(0); } uintptr_t pios_sbus_rcvr_id; if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; } #endif /* PIOS_INCLUDE_SBUS */ break; case HWFLYINGF4_UART1_DSM: #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart1_dsm_hsum_cfg, &pios_usart1_dsm_aux_cfg, &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ break; case HWFLYINGF4_UART1_HOTTSUMD: case HWFLYINGF4_UART1_HOTTSUMH: #if defined(PIOS_INCLUDE_HSUM) { enum pios_hsum_proto proto; switch (hw_uart1) { case HWFLYINGF4_UART1_HOTTSUMD: proto = PIOS_HSUM_PROTO_SUMD; break; case HWFLYINGF4_UART1_HOTTSUMH: proto = PIOS_HSUM_PROTO_SUMH; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_hsum(&pios_usart1_dsm_hsum_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); } #endif /* PIOS_INCLUDE_HSUM */ break; case HWFLYINGF4_UART1_PICOC: #if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); #endif /* PIOS_INCLUDE_PICOC */ break; } /* UART2 Port */ uint8_t hw_uart2; HwFlyingF4Uart2Get(&hw_uart2); switch (hw_uart2) { case HWFLYINGF4_UART2_DISABLED: break; case HWFLYINGF4_UART2_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); #endif /* PIOS_INCLUDE_TELEMETRY_RF */ break; case HWFLYINGF4_UART2_GPS: #if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); #endif break; case HWFLYINGF4_UART2_DSM: #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart2_dsm_hsum_cfg, &pios_usart2_dsm_aux_cfg, &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ break; case HWFLYINGF4_UART2_HOTTSUMD: case HWFLYINGF4_UART2_HOTTSUMH: #if defined(PIOS_INCLUDE_HSUM) { enum pios_hsum_proto proto; switch (hw_uart2) { case HWFLYINGF4_UART2_HOTTSUMD: proto = PIOS_HSUM_PROTO_SUMD; break; case HWFLYINGF4_UART2_HOTTSUMH: proto = PIOS_HSUM_PROTO_SUMH; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_hsum(&pios_usart2_dsm_hsum_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); } #endif /* PIOS_INCLUDE_HSUM */ break; case HWFLYINGF4_UART2_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ break; case HWFLYINGF4_UART2_COMBRIDGE: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); #endif break; case HWFLYINGF4_UART2_MAVLINKTX: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_usart2_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWFLYINGF4_UART2_MAVLINKTX_GPS_RX: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); pios_com_mavlink_id = pios_com_gps_id; #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWFLYINGF4_UART2_FRSKYSENSORHUB: #if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); #endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ break; case HWFLYINGF4_UART2_LIGHTTELEMETRYTX: #if defined(PIOS_INCLUDE_LIGHTTELEMETRY) PIOS_Board_configure_com(&pios_usart2_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); #endif break; case HWFLYINGF4_UART2_PICOC: #if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); #endif /* PIOS_INCLUDE_PICOC */ break; case HWFLYINGF4_UART2_FRSKYSPORTTELEMETRY: #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); #endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ break; } /* UART3 Port */ uint8_t hw_uart3; HwFlyingF4Uart3Get(&hw_uart3); switch (hw_uart3) { case HWFLYINGF4_UART3_DISABLED: break; case HWFLYINGF4_UART3_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); #endif /* PIOS_INCLUDE_TELEMETRY_RF */ break; case HWFLYINGF4_UART3_GPS: #if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); #endif break; case HWFLYINGF4_UART3_DSM: #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart3_dsm_hsum_cfg, &pios_usart3_dsm_aux_cfg, &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ case HWFLYINGF4_UART3_HOTTSUMD: case HWFLYINGF4_UART3_HOTTSUMH: #if defined(PIOS_INCLUDE_HSUM) { enum pios_hsum_proto proto; switch (hw_uart3) { case HWFLYINGF4_UART3_HOTTSUMD: proto = PIOS_HSUM_PROTO_SUMD; break; case HWFLYINGF4_UART3_HOTTSUMH: proto = PIOS_HSUM_PROTO_SUMH; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_hsum(&pios_usart3_dsm_hsum_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); } #endif /* PIOS_INCLUDE_HSUM */ break; case HWFLYINGF4_UART3_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ break; case HWFLYINGF4_UART3_COMBRIDGE: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); #endif break; case HWFLYINGF4_UART3_MAVLINKTX: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWFLYINGF4_UART3_MAVLINKTX_GPS_RX: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); pios_com_mavlink_id = pios_com_gps_id; #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWFLYINGF4_UART3_FRSKYSENSORHUB: #if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); #endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ break; case HWFLYINGF4_UART3_LIGHTTELEMETRYTX: #if defined(PIOS_INCLUDE_LIGHTTELEMETRY) PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); #endif break; case HWFLYINGF4_UART3_PICOC: #if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); #endif /* PIOS_INCLUDE_PICOC */ break; case HWFLYINGF4_UART3_FRSKYSPORTTELEMETRY: #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); #endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ } /* Configure the rcvr port */ uint8_t hw_rcvrport; HwFlyingF4RcvrPortGet(&hw_rcvrport); switch (hw_rcvrport) { case HWFLYINGF4_RCVRPORT_DISABLED: break; case HWFLYINGF4_RCVRPORT_PWM: #if defined(PIOS_INCLUDE_PWM) { uintptr_t pios_pwm_id; PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); uintptr_t pios_pwm_rcvr_id; if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } #endif /* PIOS_INCLUDE_PWM */ break; case HWFLYINGF4_RCVRPORT_PPM: case HWFLYINGF4_RCVRPORT_PPMOUTPUTS: #if defined(PIOS_INCLUDE_PPM) { uintptr_t pios_ppm_id; PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); uintptr_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; } #endif /* PIOS_INCLUDE_PPM */ break; case HWFLYINGF4_RCVRPORT_PPMPWM: /* This is a combination of PPM and PWM inputs */ #if defined(PIOS_INCLUDE_PPM) { uintptr_t pios_ppm_id; PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); uintptr_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; } #endif /* PIOS_INCLUDE_PPM */ #if defined(PIOS_INCLUDE_PWM) { uintptr_t pios_pwm_id; PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_with_ppm_cfg); uintptr_t pios_pwm_rcvr_id; if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } #endif /* PIOS_INCLUDE_PWM */ break; } #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); uintptr_t pios_gcsrcvr_id; PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); uintptr_t pios_gcsrcvr_rcvr_id; if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; #endif /* PIOS_INCLUDE_GCSRCVR */ #ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS switch (hw_rcvrport) { case HWFLYINGF4_RCVRPORT_DISABLED: case HWFLYINGF4_RCVRPORT_PWM: case HWFLYINGF4_RCVRPORT_PPM: /* Set up the servo outputs */ #ifdef PIOS_INCLUDE_SERVO PIOS_Servo_Init(&pios_servo_cfg); #endif break; case HWFLYINGF4_RCVRPORT_PPMOUTPUTS: case HWFLYINGF4_RCVRPORT_OUTPUTS: #ifdef PIOS_INCLUDE_SERVO PIOS_Servo_Init(&pios_servo_rcvr_cfg); #endif break; } #else PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); #endif PIOS_WDG_Clear(); PIOS_DELAY_WaitmS(200); PIOS_WDG_Clear(); #if defined(PIOS_INCLUDE_I2C) if (PIOS_I2C_Init(&pios_i2c_10dof_adapter_id, &pios_i2c_10dof_adapter_cfg)) { PIOS_DEBUG_Assert(0); } if (PIOS_I2C_CheckClear(pios_i2c_10dof_adapter_id) != 0) panic(5); #if defined(PIOS_INCLUDE_MPU6050) if (PIOS_MPU6050_Init(pios_i2c_10dof_adapter_id, PIOS_MPU6050_I2C_ADD_A0_LOW, &pios_mpu6050_cfg) != 0) panic(2); if (PIOS_MPU6050_Test() != 0) panic(2); // To be safe map from UAVO enum to driver enum uint8_t hw_gyro_range; HwFlyingF4GyroRangeGet(&hw_gyro_range); switch(hw_gyro_range) { case HWFLYINGF4_GYRORANGE_250: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); break; case HWFLYINGF4_GYRORANGE_500: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); break; case HWFLYINGF4_GYRORANGE_1000: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); break; case HWFLYINGF4_GYRORANGE_2000: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); break; } uint8_t hw_accel_range; HwFlyingF4AccelRangeGet(&hw_accel_range); switch(hw_accel_range) { case HWFLYINGF4_ACCELRANGE_2G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); break; case HWFLYINGF4_ACCELRANGE_4G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); break; case HWFLYINGF4_ACCELRANGE_8G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); break; case HWFLYINGF4_ACCELRANGE_16G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); break; } // the filter has to be set before rate else divisor calculation will fail uint8_t hw_mpu6050_dlpf; HwFlyingF4MPU6050DLPFGet(&hw_mpu6050_dlpf); enum pios_mpu60x0_filter mpu6050_dlpf = \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_256) ? PIOS_MPU60X0_LOWPASS_256_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_188) ? PIOS_MPU60X0_LOWPASS_188_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_98) ? PIOS_MPU60X0_LOWPASS_98_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_42) ? PIOS_MPU60X0_LOWPASS_42_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_20) ? PIOS_MPU60X0_LOWPASS_20_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_10) ? PIOS_MPU60X0_LOWPASS_10_HZ : \ (hw_mpu6050_dlpf == HWFLYINGF4_MPU6050DLPF_5) ? PIOS_MPU60X0_LOWPASS_5_HZ : \ pios_mpu6050_cfg.default_filter; PIOS_MPU6050_SetLPF(mpu6050_dlpf); uint8_t hw_mpu6050_samplerate; HwFlyingF4MPU6050RateGet(&hw_mpu6050_samplerate); uint16_t mpu6050_samplerate = \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_200) ? 200 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_333) ? 333 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_500) ? 500 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_666) ? 666 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_1000) ? 1000 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_2000) ? 2000 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_4000) ? 4000 : \ (hw_mpu6050_samplerate == HWFLYINGF4_MPU6050RATE_8000) ? 8000 : \ pios_mpu6050_cfg.default_samplerate; PIOS_MPU6050_SetSampleRate(mpu6050_samplerate); PIOS_MPU6050_SetPassThrough(true); #endif /* PIOS_INCLUDE_MPU6050 */ PIOS_WDG_Clear(); PIOS_DELAY_WaitmS(50); PIOS_WDG_Clear(); #if defined(PIOS_INCLUDE_HMC5883) { uint8_t Magnetometer; HwFlyingF4MagnetometerGet(&Magnetometer); if (Magnetometer == HWFLYINGF4_MAGNETOMETER_EXTERNALI2C) { if (PIOS_HMC5883_Init(pios_i2c_10dof_adapter_id, &pios_hmc5883_external_cfg) != 0) panic(3); if (PIOS_HMC5883_Test() != 0) panic(3); // setup sensor orientation uint8_t ExtMagOrientation; HwFlyingF4ExtMagOrientationGet(&ExtMagOrientation); enum pios_hmc5883_orientation hmc5883_orientation = \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_TOP0DEGCW) ? PIOS_HMC5883_TOP_0DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_TOP90DEGCW) ? PIOS_HMC5883_TOP_90DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_TOP180DEGCW) ? PIOS_HMC5883_TOP_180DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_TOP270DEGCW) ? PIOS_HMC5883_TOP_270DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_BOTTOM0DEGCW) ? PIOS_HMC5883_BOTTOM_0DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_BOTTOM90DEGCW) ? PIOS_HMC5883_BOTTOM_90DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_BOTTOM180DEGCW) ? PIOS_HMC5883_BOTTOM_180DEG : \ (ExtMagOrientation == HWFLYINGF4_EXTMAGORIENTATION_BOTTOM270DEGCW) ? PIOS_HMC5883_BOTTOM_270DEG : \ pios_hmc5883_external_cfg.Default_Orientation; PIOS_HMC5883_SetOrientation(hmc5883_orientation); } } #endif //I2C is slow, sensor init as well, reset watchdog to prevent reset here PIOS_WDG_Clear(); #if defined(PIOS_INCLUDE_MS5611) if (PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_10dof_adapter_id) != 0) panic(4); if (PIOS_MS5611_Test() != 0) panic(4); #endif //I2C is slow, sensor init as well, reset watchdog to prevent reset here PIOS_WDG_Clear(); #endif /* PIOS_INCLUDE_I2C */ #if defined(PIOS_INCLUDE_GPIO) PIOS_GPIO_Init(); #endif #if defined(PIOS_INCLUDE_ADC) PIOS_ADC_Init(&pios_adc_cfg); #endif /* Make sure we have at least one telemetry link configured or else fail initialization */ PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id); }
void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); const struct pios_board_info * bdinfo = &pios_board_info_blob; #if defined(PIOS_INCLUDE_LED) const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); PIOS_Assert(led_cfg); PIOS_LED_Init(led_cfg); #endif /* PIOS_INCLUDE_LED */ #if defined(PIOS_INCLUDE_I2C) if (PIOS_I2C_Init(&pios_i2c_internal_id, &pios_i2c_internal_cfg)) { PIOS_DEBUG_Assert(0); } if (PIOS_I2C_CheckClear(pios_i2c_internal_id) != 0) panic(3); #endif #if defined(PIOS_INCLUDE_CAN) if (PIOS_CAN_Init(&pios_can_id, &pios_can_cfg) != 0) panic(6); uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_CAN_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_CAN_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_can_id, &pios_can_com_driver, pios_can_id, rx_buffer, PIOS_COM_CAN_RX_BUF_LEN, tx_buffer, PIOS_COM_CAN_TX_BUF_LEN)) panic(6); pios_com_bridge_id = pios_com_can_id; #endif #if defined(PIOS_INCLUDE_FLASH) /* Inititialize all flash drivers */ if (PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg) != 0) panic(5); /* Register the partition table */ PIOS_FLASH_register_partition_table(pios_flash_partition_table, NELEMENTS(pios_flash_partition_table)); /* Mount all filesystems */ if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_internal_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS) != 0) panic(5); if (PIOS_FLASHFS_Logfs_Init(&pios_waypoints_settings_fs_id, &flashfs_internal_waypoints_cfg, FLASH_PARTITION_LABEL_WAYPOINTS) != 0) panic(5); #endif /* PIOS_INCLUDE_FLASH */ /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); HwSparkyInitialize(); ModuleSettingsInitialize(); #if defined(PIOS_INCLUDE_RTC) /* Initialize the real-time clock and its associated tick */ PIOS_RTC_Init(&pios_rtc_main_cfg); #endif #ifndef ERASE_FLASH /* Initialize watchdog as early as possible to catch faults during init * but do it only if there is no debugger connected */ if ((CoreDebug->DHCSR & CoreDebug_DHCSR_C_DEBUGEN_Msk) == 0) { PIOS_WDG_Init(); } #endif /* Initialize the alarms library */ AlarmsInitialize(); /* Initialize the task monitor library */ TaskMonitorInitialize(); /* Set up pulse timers */ PIOS_TIM_InitClock(&tim_1_brushless_cfg); PIOS_TIM_InitClock(&tim_2_brushless_cfg); PIOS_TIM_InitClock(&tim_3_brushless_cfg); PIOS_TIM_InitClock(&tim_15_brushless_cfg); PIOS_TIM_InitClock(&tim_16_brushless_cfg); /* IAP System Setup */ PIOS_IAP_Init(); uint16_t boot_count = PIOS_IAP_ReadBootCount(); if (boot_count < 3) { PIOS_IAP_WriteBootCount(++boot_count); AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); } else { /* Too many failed boot attempts, force hw config to defaults */ HwSparkySetDefaults(HwSparkyHandle(), 0); ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); } #if defined(PIOS_INCLUDE_USB) /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); /* Flags to determine if various USB interfaces are advertised */ bool usb_hid_present = false; #if defined(PIOS_INCLUDE_USB_CDC) bool usb_cdc_present = false; if (PIOS_USB_DESC_HID_CDC_Init()) { PIOS_Assert(0); } usb_hid_present = true; usb_cdc_present = true; #else if (PIOS_USB_DESC_HID_ONLY_Init()) { PIOS_Assert(0); } usb_hid_present = true; #endif uintptr_t pios_usb_id; PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_USB_CDC) uint8_t hw_usb_vcpport; /* Configure the USB VCP port */ HwSparkyUSB_VCPPortGet(&hw_usb_vcpport); if (!usb_cdc_present) { /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ hw_usb_vcpport = HWSPARKY_USB_VCPPORT_DISABLED; } switch (hw_usb_vcpport) { case HWSPARKY_USB_VCPPORT_DISABLED: break; case HWSPARKY_USB_VCPPORT_USBTELEMETRY: #if defined(PIOS_INCLUDE_COM) { uintptr_t pios_usb_cdc_id; if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; case HWSPARKY_USB_VCPPORT_COMBRIDGE: #if defined(PIOS_INCLUDE_COM) { uintptr_t pios_usb_cdc_id; if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; case HWSPARKY_USB_VCPPORT_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) { uintptr_t pios_usb_cdc_id; if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { PIOS_Assert(0); } uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, NULL, 0, tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ #endif /* PIOS_INCLUDE_COM */ break; } #endif /* PIOS_INCLUDE_USB_CDC */ #if defined(PIOS_INCLUDE_USB_HID) /* Configure the usb HID port */ uint8_t hw_usb_hidport; HwSparkyUSB_HIDPortGet(&hw_usb_hidport); if (!usb_hid_present) { /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ hw_usb_hidport = HWSPARKY_USB_HIDPORT_DISABLED; } switch (hw_usb_hidport) { case HWSPARKY_USB_HIDPORT_DISABLED: break; case HWSPARKY_USB_HIDPORT_USBTELEMETRY: #if defined(PIOS_INCLUDE_COM) { uintptr_t pios_usb_hid_id; if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { PIOS_Assert(0); } } #endif /* PIOS_INCLUDE_COM */ break; } #endif /* PIOS_INCLUDE_USB_HID */ #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ uint8_t hw_DSMxBind; HwSparkyDSMxBindGet(&hw_DSMxBind); /* UART1 Port */ uint8_t hw_flexi; HwSparkyFlexiPortGet(&hw_flexi); switch (hw_flexi) { case HWSPARKY_FLEXIPORT_DISABLED: break; case HWSPARKY_FLEXIPORT_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_flexi_usart_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); #endif /* PIOS_INCLUDE_TELEMETRY_RF */ break; case HWSPARKY_FLEXIPORT_GPS: #if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_flexi_usart_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id); #endif break; case HWSPARKY_FLEXIPORT_SBUS: #if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) { uintptr_t pios_usart_sbus_id; if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_flexi_sbus_cfg)) { PIOS_Assert(0); } uintptr_t pios_sbus_id; if (PIOS_SBus_Init(&pios_sbus_id, &pios_flexi_sbus_aux_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { PIOS_Assert(0); } uintptr_t pios_sbus_rcvr_id; if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; } #endif /* PIOS_INCLUDE_SBUS */ break; case HWSPARKY_FLEXIPORT_DSM2: case HWSPARKY_FLEXIPORT_DSMX10BIT: case HWSPARKY_FLEXIPORT_DSMX11BIT: #if defined(PIOS_INCLUDE_DSM) { enum pios_dsm_proto proto; switch (hw_flexi) { case HWSPARKY_FLEXIPORT_DSM2: proto = PIOS_DSM_PROTO_DSM2; break; case HWSPARKY_FLEXIPORT_DSMX10BIT: proto = PIOS_DSM_PROTO_DSMX10BIT; break; case HWSPARKY_FLEXIPORT_DSMX11BIT: proto = PIOS_DSM_PROTO_DSMX11BIT; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_dsm(&pios_flexi_dsm_cfg, &pios_flexi_dsm_aux_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ break; case HWSPARKY_FLEXIPORT_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_flexi_usart_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ break; case HWSPARKY_FLEXIPORT_COMBRIDGE: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_flexi_usart_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); #endif break; case HWSPARKY_FLEXIPORT_MAVLINKTX: #if defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_flexi_usart_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWSPARKY_FLEXIPORT_MAVLINKTX_GPS_RX: #if defined(PIOS_INCLUDE_GPS) #if defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_flexi_usart_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); pios_com_mavlink_id = pios_com_gps_id; #endif /* PIOS_INCLUDE_MAVLINK */ #endif /* PIOS_INCLUDE_GPS */ break; } /* UART3 Port */ uint8_t hw_main; HwSparkyMainPortGet(&hw_main); switch (hw_main) { case HWSPARKY_MAINPORT_DISABLED: break; case HWSPARKY_MAINPORT_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_main_usart_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); #endif /* PIOS_INCLUDE_TELEMETRY_RF */ break; case HWSPARKY_MAINPORT_GPS: #if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_main_usart_cfg, PIOS_COM_GPS_RX_BUF_LEN, 0, &pios_usart_com_driver, &pios_com_gps_id); #endif break; case HWSPARKY_MAINPORT_SBUS: #if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) { uintptr_t pios_usart_sbus_id; if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_main_sbus_cfg)) { PIOS_Assert(0); } uintptr_t pios_sbus_id; if (PIOS_SBus_Init(&pios_sbus_id, &pios_main_sbus_aux_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { PIOS_Assert(0); } uintptr_t pios_sbus_rcvr_id; if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; } #endif /* PIOS_INCLUDE_SBUS */ break; case HWSPARKY_MAINPORT_DSM2: case HWSPARKY_MAINPORT_DSMX10BIT: case HWSPARKY_MAINPORT_DSMX11BIT: #if defined(PIOS_INCLUDE_DSM) { enum pios_dsm_proto proto; switch (hw_main) { case HWSPARKY_MAINPORT_DSM2: proto = PIOS_DSM_PROTO_DSM2; break; case HWSPARKY_MAINPORT_DSMX10BIT: proto = PIOS_DSM_PROTO_DSMX10BIT; break; case HWSPARKY_MAINPORT_DSMX11BIT: proto = PIOS_DSM_PROTO_DSMX11BIT; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_dsm(&pios_main_dsm_cfg, &pios_main_dsm_aux_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ break; case HWSPARKY_MAINPORT_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_main_usart_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ break; case HWSPARKY_MAINPORT_COMBRIDGE: #if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) PIOS_Board_configure_com(&pios_main_usart_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); #endif break; case HWSPARKY_MAINPORT_MAVLINKTX: #if defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_main_usart_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); #endif /* PIOS_INCLUDE_MAVLINK */ break; case HWSPARKY_MAINPORT_MAVLINKTX_GPS_RX: #if defined(PIOS_INCLUDE_GPS) #if defined(PIOS_INCLUDE_MAVLINK) PIOS_Board_configure_com(&pios_main_usart_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); pios_com_mavlink_id = pios_com_gps_id; #endif /* PIOS_INCLUDE_MAVLINK */ #endif /* PIOS_INCLUDE_GPS */ break; } /* Configure the rcvr port */ uint8_t hw_rcvrport; HwSparkyRcvrPortGet(&hw_rcvrport); switch (hw_rcvrport) { case HWSPARKY_RCVRPORT_DISABLED: break; case HWSPARKY_RCVRPORT_PPM: #if defined(PIOS_INCLUDE_PPM) { uintptr_t pios_ppm_id; PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); uintptr_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; } #endif /* PIOS_INCLUDE_PPM */ break; case HWSPARKY_RCVRPORT_DSM2: case HWSPARKY_RCVRPORT_DSMX10BIT: case HWSPARKY_RCVRPORT_DSMX11BIT: #if defined(PIOS_INCLUDE_DSM) { enum pios_dsm_proto proto; switch (hw_rcvrport) { case HWSPARKY_RCVRPORT_DSM2: proto = PIOS_DSM_PROTO_DSM2; break; case HWSPARKY_RCVRPORT_DSMX10BIT: proto = PIOS_DSM_PROTO_DSMX10BIT; break; case HWSPARKY_RCVRPORT_DSMX11BIT: proto = PIOS_DSM_PROTO_DSMX11BIT; break; default: PIOS_Assert(0); break; } PIOS_Board_configure_dsm(&pios_rcvr_dsm_cfg, &pios_rcvr_dsm_aux_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); } #endif /* PIOS_INCLUDE_DSM */ break; case HWSPARKY_RCVRPORT_SBUS: #if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) { uintptr_t pios_usart_sbus_id; if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_rcvr_sbus_cfg)) { PIOS_Assert(0); } uintptr_t pios_sbus_id; if (PIOS_SBus_Init(&pios_sbus_id, &pios_rcvr_sbus_aux_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { PIOS_Assert(0); } uintptr_t pios_sbus_rcvr_id; if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; } #endif /* PIOS_INCLUDE_SBUS */ break; break; } #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); uintptr_t pios_gcsrcvr_id; PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); uintptr_t pios_gcsrcvr_rcvr_id; if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { PIOS_Assert(0); } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; #endif /* PIOS_INCLUDE_GCSRCVR */ #ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS #ifdef PIOS_INCLUDE_SERVO PIOS_Servo_Init(&pios_servo_cfg); #endif #ifdef PIOS_INCLUDE_BRUSHLESS if (PIOS_Brushless_Init(&pios_brushless_cfg) != 0) panic(8); #endif #else PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); #endif #if defined(PIOS_INCLUDE_ADC) uint32_t internal_adc_id; if(PIOS_INTERNAL_ADC_Init(&internal_adc_id, &internal_adc_cfg) < 0) PIOS_Assert(0); PIOS_ADC_Init(&pios_internal_adc_id, &pios_internal_adc_driver, internal_adc_id); #endif /* PIOS_INCLUDE_ADC */ PIOS_WDG_Clear(); PIOS_DELAY_WaitmS(200); PIOS_WDG_Clear(); #if defined(PIOS_INCLUDE_MPU9150) #if defined(PIOS_INCLUDE_MPU6050) // Enable autoprobing when both 6050 and 9050 compiled in bool mpu9150_found = false; if (PIOS_MPU9150_Probe(pios_i2c_internal_id, PIOS_MPU9150_I2C_ADD_A0_LOW) == 0) { mpu9150_found = true; #else { #endif /* PIOS_INCLUDE_MPU6050 */ int retval; retval = PIOS_MPU9150_Init(pios_i2c_internal_id, PIOS_MPU9150_I2C_ADD_A0_LOW, &pios_mpu9150_cfg); if (retval == -10) panic(1); // indicate missing IRQ separately if (retval != 0) panic(2); // To be safe map from UAVO enum to driver enum uint8_t hw_gyro_range; HwSparkyGyroRangeGet(&hw_gyro_range); switch(hw_gyro_range) { case HWSPARKY_GYRORANGE_250: PIOS_MPU9150_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); break; case HWSPARKY_GYRORANGE_500: PIOS_MPU9150_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); break; case HWSPARKY_GYRORANGE_1000: PIOS_MPU9150_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); break; case HWSPARKY_GYRORANGE_2000: PIOS_MPU9150_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); break; } uint8_t hw_accel_range; HwSparkyAccelRangeGet(&hw_accel_range); switch(hw_accel_range) { case HWSPARKY_ACCELRANGE_2G: PIOS_MPU9150_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); break; case HWSPARKY_ACCELRANGE_4G: PIOS_MPU9150_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); break; case HWSPARKY_ACCELRANGE_8G: PIOS_MPU9150_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); break; case HWSPARKY_ACCELRANGE_16G: PIOS_MPU9150_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); break; } uint8_t hw_mpu9150_dlpf; HwSparkyMPU9150DLPFGet(&hw_mpu9150_dlpf); enum pios_mpu60x0_filter mpu9150_dlpf = \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_256) ? PIOS_MPU60X0_LOWPASS_256_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_188) ? PIOS_MPU60X0_LOWPASS_188_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_98) ? PIOS_MPU60X0_LOWPASS_98_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_42) ? PIOS_MPU60X0_LOWPASS_42_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_20) ? PIOS_MPU60X0_LOWPASS_20_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_10) ? PIOS_MPU60X0_LOWPASS_10_HZ : \ (hw_mpu9150_dlpf == HWSPARKY_MPU9150DLPF_5) ? PIOS_MPU60X0_LOWPASS_5_HZ : \ pios_mpu9150_cfg.default_filter; PIOS_MPU9150_SetLPF(mpu9150_dlpf); uint8_t hw_mpu9150_samplerate; HwSparkyMPU9150RateGet(&hw_mpu9150_samplerate); uint16_t mpu9150_samplerate = \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_200) ? 200 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_333) ? 333 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_500) ? 500 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_666) ? 666 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_1000) ? 1000 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_2000) ? 2000 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_4000) ? 4000 : \ (hw_mpu9150_samplerate == HWSPARKY_MPU9150RATE_8000) ? 8000 : \ pios_mpu9150_cfg.default_samplerate; PIOS_MPU9150_SetSampleRate(mpu9150_samplerate); } #endif /* PIOS_INCLUDE_MPU9150 */ #if defined(PIOS_INCLUDE_MPU6050) #if defined(PIOS_INCLUDE_MPU9150) // MPU9150 looks like an MPU6050 _plus_ additional hardware. So we cannot try and // probe if MPU9150 is found or we will find a duplicate if (mpu9150_found == false) #endif /* PIOS_INCLUDE_MPU9150 */ { if (PIOS_MPU6050_Init(pios_i2c_internal_id, PIOS_MPU6050_I2C_ADD_A0_LOW, &pios_mpu6050_cfg) != 0) panic(2); if (PIOS_MPU6050_Test() != 0) panic(2); // To be safe map from UAVO enum to driver enum uint8_t hw_gyro_range; HwSparkyGyroRangeGet(&hw_gyro_range); switch(hw_gyro_range) { case HWSPARKY_GYRORANGE_250: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); break; case HWSPARKY_GYRORANGE_500: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); break; case HWSPARKY_GYRORANGE_1000: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); break; case HWSPARKY_GYRORANGE_2000: PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); break; } uint8_t hw_accel_range; HwSparkyAccelRangeGet(&hw_accel_range); switch(hw_accel_range) { case HWSPARKY_ACCELRANGE_2G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); break; case HWSPARKY_ACCELRANGE_4G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); break; case HWSPARKY_ACCELRANGE_8G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); break; case HWSPARKY_ACCELRANGE_16G: PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); break; } } #endif /* PIOS_INCLUDE_MPU6050 */ //I2C is slow, sensor init as well, reset watchdog to prevent reset here PIOS_WDG_Clear(); #if defined(PIOS_INCLUDE_MS5611) PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_internal_id); #endif #if defined(PIOS_INCLUDE_GPIO) PIOS_GPIO_Init(); #endif /* Make sure we have at least one telemetry link configured or else fail initialization */ PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id); }
/** * @brief Initialize the MPU6050 3-axis gyro sensor * \return none * \param[in] PIOS_MPU6050_ConfigTypeDef struct to be used to configure sensor. * */ static void PIOS_MPU6050_Config(struct pios_mpu60x0_cfg const *cfg) { #if defined(PIOS_MPU6050_SIMPLE_INIT_SEQUENCE) // Reset chip PIOS_MPU6050_SetReg(PIOS_MPU60X0_PWR_MGMT_REG, PIOS_MPU60X0_PWRMGMT_IMU_RST); // Reset sensors signal path PIOS_MPU6050_SetReg(PIOS_MPU60X0_USER_CTRL_REG, PIOS_MPU60X0_USERCTL_GYRO_RST); // Give chip some time to initialize PIOS_DELAY_WaitmS(10); //Power management configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_PWR_MGMT_REG, cfg->Pwr_mgmt_clk); // User control PIOS_MPU6050_SetReg(PIOS_MPU60X0_USER_CTRL_REG, cfg->User_ctl); // Digital low-pass filter and scale // set this before sample rate else sample rate calculation will fail PIOS_MPU6050_SetLPF(cfg->default_filter); // Sample rate PIOS_MPU6050_SetSampleRate(cfg->default_samplerate); // Set the gyro scale PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); #if defined(PIOS_MPU6050_ACCEL) // Set the accel scale PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); #endif /* PIOS_MPU6050_ACCEL */ // Interrupt configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_CFG_REG, cfg->interrupt_cfg); // Interrupt enable PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_EN_REG, cfg->interrupt_en); #else /* PIOS_MPU6050_SIMPLE_INIT_SEQUENCE */ /* This init sequence should really be dropped in favor of something * less redundant but it seems to be hard to get it running well * on all different targets. */ // Reset chip PIOS_MPU6050_SetReg(PIOS_MPU60X0_PWR_MGMT_REG, 0x80 | cfg->Pwr_mgmt_clk); do { PIOS_DELAY_WaitmS(5); } while (PIOS_MPU6050_GetReg(PIOS_MPU60X0_PWR_MGMT_REG) & 0x80); PIOS_DELAY_WaitmS(25); // Reset chip and fifo PIOS_MPU6050_SetReg(PIOS_MPU60X0_USER_CTRL_REG, 0x80 | 0x01 | 0x02 | 0x04); do { PIOS_DELAY_WaitmS(5); } while (PIOS_MPU6050_GetReg(PIOS_MPU60X0_USER_CTRL_REG) & 0x07); PIOS_DELAY_WaitmS(25); //Power management configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_PWR_MGMT_REG, cfg->Pwr_mgmt_clk); // Interrupt configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_CFG_REG, cfg->interrupt_cfg); // Interrupt enable PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_EN_REG, cfg->interrupt_en); #if defined(PIOS_MPU6050_ACCEL) // Set the accel scale PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); #endif // Digital low-pass filter and scale // set this before sample rate else sample rate calculation will fail PIOS_MPU6050_SetLPF(cfg->default_filter); // Sample rate PIOS_MPU6050_SetSampleRate(cfg->default_samplerate); // Set the gyro scale PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); // User control PIOS_MPU6050_SetReg(PIOS_MPU60X0_USER_CTRL_REG, cfg->User_ctl); //Power management configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_PWR_MGMT_REG, cfg->Pwr_mgmt_clk); // Interrupt configuration PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_CFG_REG, cfg->interrupt_cfg); // Interrupt enable PIOS_MPU6050_SetReg(PIOS_MPU60X0_INT_EN_REG, cfg->interrupt_en); #endif /* PIOS_MPU6050_SIMPLE_INIT_SEQUENCE */ }