├── .gitignore ├── .mxproject ├── Documentation └── Release_Notes.md ├── Drivers ├── BSP │ ├── BSP_accelero.c │ ├── BSP_accelero.h │ ├── BSP_gyro.c │ ├── BSP_gyro.h │ ├── BSP_magneto.c │ ├── BSP_magneto.h │ ├── BSP_pressure.c │ ├── BSP_pressure.h │ ├── Common │ │ ├── accelerometer.h │ │ ├── component.h │ │ ├── gyroscope.h │ │ ├── magnetometer.h │ │ ├── pressure.h │ │ └── sensor.h │ ├── hts221 │ │ ├── HTS221_Driver.c │ │ ├── HTS221_Driver.h │ │ ├── HTS221_Driver_HL.c │ │ ├── HTS221_Driver_HL.h │ │ └── Release_Notes.html │ ├── lsm303agr │ │ ├── LSM303AGR_ACC_driver.c │ │ ├── LSM303AGR_ACC_driver.h │ │ ├── LSM303AGR_ACC_driver_HL.c │ │ ├── LSM303AGR_ACC_driver_HL.h │ │ ├── LSM303AGR_Combo_driver_HL.h │ │ ├── LSM303AGR_MAG_driver.c │ │ ├── LSM303AGR_MAG_driver.h │ │ ├── LSM303AGR_MAG_driver_HL.c │ │ ├── LSM303AGR_MAG_driver_HL.h │ │ └── Release_Notes.html │ ├── lsm6dsm │ │ ├── LSM6DSM_ACC_GYRO_driver.c │ │ ├── LSM6DSM_ACC_GYRO_driver.h │ │ ├── LSM6DSM_ACC_GYRO_driver_HL.c │ │ └── LSM6DSM_ACC_GYRO_driver_HL.h │ └── mpu9250 │ │ ├── mpu9250.c │ │ └── mpu9250.h ├── CMSIS │ ├── Device │ │ └── ST │ │ │ └── STM32F7xx │ │ │ ├── Include │ │ │ ├── stm32f767xx.h │ │ │ ├── stm32f7xx.h │ │ │ └── system_stm32f7xx.h │ │ │ └── Source │ │ │ └── Templates │ │ │ └── iar │ │ │ └── startup_stm32f767xx.s │ └── Include │ │ ├── arm_common_tables.h │ │ ├── arm_const_structs.h │ │ ├── arm_math.h │ │ ├── cmsis_armcc.h │ │ ├── cmsis_armcc_V6.h │ │ ├── cmsis_gcc.h │ │ ├── core_cm0.h │ │ ├── core_cm0plus.h │ │ ├── core_cm3.h │ │ ├── core_cm4.h │ │ ├── core_cm7.h │ │ ├── core_cmFunc.h │ │ ├── core_cmInstr.h │ │ ├── core_cmSimd.h │ │ ├── core_sc000.h │ │ └── core_sc300.h ├── STM32F7xx_HAL_Driver │ ├── Inc │ │ ├── Legacy │ │ │ └── stm32_hal_legacy.h │ │ ├── stm32f7xx_hal.h │ │ ├── stm32f7xx_hal_adc.h │ │ ├── stm32f7xx_hal_adc_ex.h │ │ ├── stm32f7xx_hal_can.h │ │ ├── stm32f7xx_hal_cortex.h │ │ ├── stm32f7xx_hal_def.h │ │ ├── stm32f7xx_hal_dma.h │ │ ├── stm32f7xx_hal_dma_ex.h │ │ ├── stm32f7xx_hal_eth.h │ │ ├── stm32f7xx_hal_flash.h │ │ ├── stm32f7xx_hal_flash_ex.h │ │ ├── stm32f7xx_hal_gpio.h │ │ ├── stm32f7xx_hal_gpio_ex.h │ │ ├── stm32f7xx_hal_i2c.h │ │ ├── stm32f7xx_hal_i2c_ex.h │ │ ├── stm32f7xx_hal_mmc.h │ │ ├── stm32f7xx_hal_pcd.h │ │ ├── stm32f7xx_hal_pcd_ex.h │ │ ├── stm32f7xx_hal_pwr.h │ │ ├── stm32f7xx_hal_pwr_ex.h │ │ ├── stm32f7xx_hal_qspi.h │ │ ├── stm32f7xx_hal_rcc.h │ │ ├── stm32f7xx_hal_rcc_ex.h │ │ ├── stm32f7xx_hal_sai.h │ │ ├── stm32f7xx_hal_sai_ex.h │ │ ├── stm32f7xx_hal_sd.h │ │ ├── stm32f7xx_hal_spi.h │ │ ├── stm32f7xx_hal_tim.h │ │ ├── stm32f7xx_hal_tim_ex.h │ │ ├── stm32f7xx_hal_uart.h │ │ ├── stm32f7xx_hal_uart_ex.h │ │ ├── stm32f7xx_ll_bus.h │ │ ├── stm32f7xx_ll_dma.h │ │ ├── stm32f7xx_ll_gpio.h │ │ ├── stm32f7xx_ll_rcc.h │ │ ├── stm32f7xx_ll_sdmmc.h │ │ ├── stm32f7xx_ll_spi.h │ │ ├── stm32f7xx_ll_tim.h │ │ ├── stm32f7xx_ll_usart.h │ │ └── stm32f7xx_ll_usb.h │ └── Src │ │ ├── stm32f7xx_hal.c │ │ ├── stm32f7xx_hal_adc.c │ │ ├── stm32f7xx_hal_adc_ex.c │ │ ├── stm32f7xx_hal_can.c │ │ ├── stm32f7xx_hal_cortex.c │ │ ├── stm32f7xx_hal_dma.c │ │ ├── stm32f7xx_hal_dma_ex.c │ │ ├── stm32f7xx_hal_eth.c │ │ ├── stm32f7xx_hal_flash.c │ │ ├── stm32f7xx_hal_flash_ex.c │ │ ├── stm32f7xx_hal_gpio.c │ │ ├── stm32f7xx_hal_i2c.c │ │ ├── stm32f7xx_hal_i2c_ex.c │ │ ├── stm32f7xx_hal_mmc.c │ │ ├── stm32f7xx_hal_pcd.c │ │ ├── stm32f7xx_hal_pcd_ex.c │ │ ├── stm32f7xx_hal_pwr.c │ │ ├── stm32f7xx_hal_pwr_ex.c │ │ ├── stm32f7xx_hal_qspi.c │ │ ├── stm32f7xx_hal_rcc.c │ │ ├── stm32f7xx_hal_rcc_ex.c │ │ ├── stm32f7xx_hal_sai.c │ │ ├── stm32f7xx_hal_sai_ex.c │ │ ├── stm32f7xx_hal_sd.c │ │ ├── stm32f7xx_hal_spi.c │ │ ├── stm32f7xx_hal_tim.c │ │ ├── stm32f7xx_hal_tim_ex.c │ │ ├── stm32f7xx_hal_uart.c │ │ ├── stm32f7xx_ll_dma.c │ │ ├── stm32f7xx_ll_gpio.c │ │ ├── stm32f7xx_ll_sdmmc.c │ │ ├── stm32f7xx_ll_spi.c │ │ ├── stm32f7xx_ll_tim.c │ │ ├── stm32f7xx_ll_usart.c │ │ └── stm32f7xx_ll_usb.c ├── gpio.c ├── gpio.h ├── spi.c ├── spi.h ├── stm32f7xx_hal_msp.c ├── stm32f7xx_it.c ├── stm32f7xx_it.h ├── tim.c ├── tim.h ├── usart.c └── usart.h ├── EEDrone.ioc ├── EWARM ├── EEDrone.ewd ├── EEDrone.ewp ├── Project.eww ├── startup_stm32f767xx.s ├── stm32f767xx_ITCM_flash.icf ├── stm32f767xx_flash.icf └── stm32f767xx_sram.icf ├── Example ├── AHRS_Test │ ├── main.c │ ├── system.c │ └── system.h ├── DSP_Test │ └── main.c ├── FreeRTOS_Test │ ├── freertos.c │ └── main.c ├── MavLink_Test │ ├── main.c │ ├── mavlink.c │ ├── system.c │ └── system.h ├── Sensor_Test │ ├── main.c │ ├── system.c │ └── system.h ├── UART_DMA_Test │ └── main.c └── UART_Test │ └── main.c ├── Inc ├── FreeRTOSConfig.h ├── adc.h ├── bsp_driver_sd.h ├── can.h ├── config.h ├── eth.h ├── ethernetif.h ├── fatfs.h ├── ffconf.h ├── gpio.h ├── i2c.h ├── lwip.h ├── lwipopts.h ├── main.h ├── quadspi.h ├── sai.h ├── sdmmc.h ├── stm32f7xx_hal_conf.h ├── stm32f7xx_it.h ├── usb_device.h ├── usbd_cdc_if.h ├── usbd_conf.h └── usbd_desc.h ├── LICENSE.md ├── Middlewares ├── ST │ └── STM32_USB_Device_Library │ │ ├── Class │ │ └── CDC │ │ │ ├── Inc │ │ │ └── usbd_cdc.h │ │ │ └── Src │ │ │ └── usbd_cdc.c │ │ └── Core │ │ ├── Inc │ │ ├── usbd_core.h │ │ ├── usbd_ctlreq.h │ │ ├── usbd_def.h │ │ └── usbd_ioreq.h │ │ └── Src │ │ ├── usbd_core.c │ │ ├── usbd_ctlreq.c │ │ └── usbd_ioreq.c └── Third_Party │ ├── FatFs │ └── src │ │ ├── diskio.c │ │ ├── diskio.h │ │ ├── drivers │ │ ├── sd_diskio.c │ │ └── sd_diskio.h │ │ ├── ff.c │ │ ├── ff.h │ │ ├── ff_gen_drv.c │ │ ├── ff_gen_drv.h │ │ ├── ffconf_template.h │ │ ├── integer.h │ │ └── option │ │ └── syscall.c │ ├── FreeRTOS-Plus-CLI │ ├── CLI_Commands.c │ ├── FreeRTOS_CLI.c │ ├── FreeRTOS_CLI.h │ ├── UARTCommandConsole.c │ ├── serial.c │ └── serial.h │ └── FreeRTOS │ └── Source │ ├── CMSIS_RTOS │ ├── cmsis_os.c │ └── cmsis_os.h │ ├── UARTCommandConsole.c │ ├── croutine.c │ ├── event_groups.c │ ├── include │ ├── FreeRTOS.h │ ├── FreeRTOSConfig_template.h │ ├── StackMacros.h │ ├── croutine.h │ ├── deprecated_definitions.h │ ├── event_groups.h │ ├── list.h │ ├── mpu_prototypes.h │ ├── mpu_wrappers.h │ ├── portable.h │ ├── projdefs.h │ ├── queue.h │ ├── semphr.h │ ├── task.h │ └── timers.h │ ├── list.c │ ├── portable │ ├── IAR │ │ └── ARM_CM7 │ │ │ └── r0p1 │ │ │ ├── port.c │ │ │ ├── portasm.s │ │ │ └── portmacro.h │ └── MemMang │ │ └── heap_4.c │ ├── queue.c │ ├── tasks.c │ └── timers.c ├── Modules ├── AHRS │ ├── CKF.C │ ├── CKF.h │ ├── Double.h │ ├── EKF.c │ ├── EKF.h │ ├── INS_EKF.c │ ├── INS_EKF.h │ ├── Quaternion.c │ ├── Quaternion.h │ ├── SRCKF.c │ ├── SRCKF.h │ ├── UKF.c │ ├── UKF.h │ ├── miniAHRS │ │ ├── miniAHRS.c │ │ └── miniAHRS.h │ └── miniIMU │ │ ├── FP │ │ ├── FP_Math.c │ │ ├── FP_Math.h │ │ ├── FP_Matrix.c │ │ ├── FP_Matrix.h │ │ ├── FP_miniIMU.c │ │ └── FP_miniIMU.h │ │ ├── Usage.txt │ │ ├── miniIMU.c │ │ ├── miniIMU.h │ │ ├── miniMatrix.c │ │ └── miniMatrix.h ├── Math │ ├── FastMath.c │ └── FastMath.h ├── Matrix │ ├── DoubleMatrix.c │ ├── DoubleMatrix.h │ ├── Matrix.c │ └── Matrix.h └── MavLink │ ├── checksum.h │ ├── common │ ├── common.h │ ├── mavlink.h │ ├── mavlink_msg_actuator_control_target.h │ ├── mavlink_msg_adsb_vehicle.h │ ├── mavlink_msg_altitude.h │ ├── mavlink_msg_att_pos_mocap.h │ ├── mavlink_msg_attitude.h │ ├── mavlink_msg_attitude_quaternion.h │ ├── mavlink_msg_attitude_quaternion_cov.h │ ├── mavlink_msg_attitude_target.h │ ├── mavlink_msg_auth_key.h │ ├── mavlink_msg_autopilot_version.h │ ├── mavlink_msg_battery_status.h │ ├── mavlink_msg_camera_trigger.h │ ├── mavlink_msg_change_operator_control.h │ ├── mavlink_msg_change_operator_control_ack.h │ ├── mavlink_msg_collision.h │ ├── mavlink_msg_command_ack.h │ ├── mavlink_msg_command_int.h │ ├── mavlink_msg_command_long.h │ ├── mavlink_msg_control_system_state.h │ ├── mavlink_msg_data_stream.h │ ├── mavlink_msg_data_transmission_handshake.h │ ├── mavlink_msg_debug.h │ ├── mavlink_msg_debug_vect.h │ ├── mavlink_msg_distance_sensor.h │ ├── mavlink_msg_encapsulated_data.h │ ├── mavlink_msg_estimator_status.h │ ├── mavlink_msg_extended_sys_state.h │ ├── mavlink_msg_file_transfer_protocol.h │ ├── mavlink_msg_follow_target.h │ ├── mavlink_msg_global_position_int.h │ ├── mavlink_msg_global_position_int_cov.h │ ├── mavlink_msg_global_vision_position_estimate.h │ ├── mavlink_msg_gps2_raw.h │ ├── mavlink_msg_gps2_rtk.h │ ├── mavlink_msg_gps_global_origin.h │ ├── mavlink_msg_gps_inject_data.h │ ├── mavlink_msg_gps_input.h │ ├── mavlink_msg_gps_raw_int.h │ ├── mavlink_msg_gps_rtcm_data.h │ ├── mavlink_msg_gps_rtk.h │ ├── mavlink_msg_gps_status.h │ ├── mavlink_msg_heartbeat.h │ ├── mavlink_msg_high_latency.h │ ├── mavlink_msg_highres_imu.h │ ├── mavlink_msg_hil_actuator_controls.h │ ├── mavlink_msg_hil_controls.h │ ├── mavlink_msg_hil_gps.h │ ├── mavlink_msg_hil_optical_flow.h │ ├── mavlink_msg_hil_rc_inputs_raw.h │ ├── mavlink_msg_hil_sensor.h │ ├── mavlink_msg_hil_state.h │ ├── mavlink_msg_hil_state_quaternion.h │ ├── mavlink_msg_home_position.h │ ├── mavlink_msg_landing_target.h │ ├── mavlink_msg_local_position_ned.h │ ├── mavlink_msg_local_position_ned_cov.h │ ├── mavlink_msg_local_position_ned_system_global_offset.h │ ├── mavlink_msg_log_data.h │ ├── mavlink_msg_log_entry.h │ ├── mavlink_msg_log_erase.h │ ├── mavlink_msg_log_request_data.h │ ├── mavlink_msg_log_request_end.h │ ├── mavlink_msg_log_request_list.h │ ├── mavlink_msg_manual_control.h │ ├── mavlink_msg_manual_setpoint.h │ ├── mavlink_msg_memory_vect.h │ ├── mavlink_msg_message_interval.h │ ├── mavlink_msg_mission_ack.h │ ├── mavlink_msg_mission_clear_all.h │ ├── mavlink_msg_mission_count.h │ ├── mavlink_msg_mission_current.h │ ├── mavlink_msg_mission_item.h │ ├── mavlink_msg_mission_item_int.h │ ├── mavlink_msg_mission_item_reached.h │ ├── mavlink_msg_mission_request.h │ ├── mavlink_msg_mission_request_int.h │ ├── mavlink_msg_mission_request_list.h │ ├── mavlink_msg_mission_request_partial_list.h │ ├── mavlink_msg_mission_set_current.h │ ├── mavlink_msg_mission_write_partial_list.h │ ├── mavlink_msg_named_value_float.h │ ├── mavlink_msg_named_value_int.h │ ├── mavlink_msg_nav_controller_output.h │ ├── mavlink_msg_optical_flow.h │ ├── mavlink_msg_optical_flow_rad.h │ ├── mavlink_msg_param_map_rc.h │ ├── mavlink_msg_param_request_list.h │ ├── mavlink_msg_param_request_read.h │ ├── mavlink_msg_param_set.h │ ├── mavlink_msg_param_value.h │ ├── mavlink_msg_ping.h │ ├── mavlink_msg_position_target_global_int.h │ ├── mavlink_msg_position_target_local_ned.h │ ├── mavlink_msg_power_status.h │ ├── mavlink_msg_radio_status.h │ ├── mavlink_msg_raw_imu.h │ ├── mavlink_msg_raw_pressure.h │ ├── mavlink_msg_rc_channels.h │ ├── mavlink_msg_rc_channels_override.h │ ├── mavlink_msg_rc_channels_raw.h │ ├── mavlink_msg_rc_channels_scaled.h │ ├── mavlink_msg_request_data_stream.h │ ├── mavlink_msg_resource_request.h │ ├── mavlink_msg_safety_allowed_area.h │ ├── mavlink_msg_safety_set_allowed_area.h │ ├── mavlink_msg_scaled_imu.h │ ├── mavlink_msg_scaled_imu2.h │ ├── mavlink_msg_scaled_imu3.h │ ├── mavlink_msg_scaled_pressure.h │ ├── mavlink_msg_scaled_pressure2.h │ ├── mavlink_msg_scaled_pressure3.h │ ├── mavlink_msg_serial_control.h │ ├── mavlink_msg_servo_output_raw.h │ ├── mavlink_msg_set_actuator_control_target.h │ ├── mavlink_msg_set_attitude_target.h │ ├── mavlink_msg_set_gps_global_origin.h │ ├── mavlink_msg_set_home_position.h │ ├── mavlink_msg_set_mode.h │ ├── mavlink_msg_set_position_target_global_int.h │ ├── mavlink_msg_set_position_target_local_ned.h │ ├── mavlink_msg_sim_state.h │ ├── mavlink_msg_statustext.h │ ├── mavlink_msg_sys_status.h │ ├── mavlink_msg_system_time.h │ ├── mavlink_msg_terrain_check.h │ ├── mavlink_msg_terrain_data.h │ ├── mavlink_msg_terrain_report.h │ ├── mavlink_msg_terrain_request.h │ ├── mavlink_msg_timesync.h │ ├── mavlink_msg_v2_extension.h │ ├── mavlink_msg_vfr_hud.h │ ├── mavlink_msg_vibration.h │ ├── mavlink_msg_vicon_position_estimate.h │ ├── mavlink_msg_vision_position_estimate.h │ ├── mavlink_msg_vision_speed_estimate.h │ ├── mavlink_msg_wind_cov.h │ ├── testsuite.h │ └── version.h │ ├── mavlink_conversions.h │ ├── mavlink_helpers.h │ ├── mavlink_types.h │ └── protocol.h ├── README.md └── Src ├── adc.c ├── bsp_driver_sd.c ├── can.c ├── eth.c ├── ethernetif.c ├── fatfs.c ├── freertos.c ├── gpio.c ├── i2c.c ├── lwip.c ├── main.c ├── quadspi.c ├── sai.c ├── sdmmc.c ├── spi.c ├── stm32f7xx_hal_msp.c ├── stm32f7xx_it.c ├── system_stm32f7xx.c ├── tim.c ├── usart.c ├── usb_device.c ├── usbd_cdc_if.c ├── usbd_conf.c └── usbd_desc.c /.gitignore: -------------------------------------------------------------------------------- 1 | EWARM/** 2 | !*.icf 3 | !*.eww 4 | !*.ewp 5 | !*.ewd 6 | !*.s 7 | MDK-ARM/** 8 | !*.uvoptx 9 | !*.uvprojx 10 | !*.s 11 | SW4STM32/EEDrone/** 12 | !*.cproject 13 | !*.project 14 | !*.xml 15 | !*.ld 16 | SI/ -------------------------------------------------------------------------------- /.mxproject: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/.mxproject -------------------------------------------------------------------------------- /Documentation/Release_Notes.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Documentation/Release_Notes.md -------------------------------------------------------------------------------- /Drivers/BSP/Common/component.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file component.h 4 | * @author MEMS Application Team 5 | * @version V3.0.0 6 | * @date 12-August-2016 7 | * @brief This header file contains the functions prototypes common for all 8 | * drivers 9 | ****************************************************************************** 10 | * @attention 11 | * 12 | *

© COPYRIGHT(c) 2016 STMicroelectronics

13 | * 14 | * Redistribution and use in source and binary forms, with or without modification, 15 | * are permitted provided that the following conditions are met: 16 | * 1. Redistributions of source code must retain the above copyright notice, 17 | * this list of conditions and the following disclaimer. 18 | * 2. Redistributions in binary form must reproduce the above copyright notice, 19 | * this list of conditions and the following disclaimer in the documentation 20 | * and/or other materials provided with the distribution. 21 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 22 | * may be used to endorse or promote products derived from this software 23 | * without specific prior written permission. 24 | * 25 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 28 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 29 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 30 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 31 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 32 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 33 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 34 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 35 | * 36 | ****************************************************************************** 37 | */ 38 | 39 | /* Define to prevent recursive inclusion -------------------------------------*/ 40 | #ifndef __COMPONENT_H 41 | #define __COMPONENT_H 42 | 43 | #ifdef __cplusplus 44 | extern "C" { 45 | #endif 46 | 47 | 48 | 49 | /* Includes ------------------------------------------------------------------*/ 50 | 51 | #include 52 | 53 | /** @addtogroup BSP BSP 54 | * @{ 55 | */ 56 | 57 | /** @addtogroup COMPONENTS COMPONENTS 58 | * @{ 59 | */ 60 | 61 | /** @addtogroup COMMON COMMON 62 | * @{ 63 | */ 64 | 65 | /** @addtogroup COMPONENT COMPONENT 66 | * @{ 67 | */ 68 | 69 | /** @addtogroup COMPONENT_Public_Constants Public constants 70 | * @{ 71 | */ 72 | 73 | /** 74 | * @brief NULL pointer definition 75 | */ 76 | #ifndef NULL 77 | #define NULL ( void * )0 78 | #endif 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | /** @addtogroup COMPONENT_Public_Types COMPONENT Public Types 85 | * @{ 86 | */ 87 | 88 | /** 89 | * @brief Component's Context structure definition. 90 | */ 91 | typedef struct 92 | { 93 | 94 | /* Identity */ 95 | uint8_t who_am_i; 96 | 97 | /* Configuration */ 98 | uint8_t ifType; /* 0 means I2C, 1 means SPI, etc. */ 99 | uint8_t address; /* Sensor I2C address (NOTE: Not a unique sensor ID). */ 100 | uint8_t spiDevice; /* Sensor Chip Select for SPI Bus */ 101 | uint8_t instance; /* Sensor instance (NOTE: Sensor ID unique only within its class). */ 102 | uint8_t isInitialized; /* Sensor setup done. */ 103 | uint8_t isEnabled; /* Sensor ON. */ 104 | uint8_t isCombo; /* Combo sensor (component consists of more sensors). */ 105 | 106 | /* Pointer to the Data */ 107 | void *pData; 108 | 109 | /* Pointer to the Virtual Table */ 110 | void *pVTable; 111 | /* Pointer to the Extended Virtual Table */ 112 | void *pExtVTable; 113 | } DrvContextTypeDef; 114 | 115 | 116 | 117 | /** 118 | * @brief Component's Status enumerator definition. 119 | */ 120 | typedef enum 121 | { 122 | COMPONENT_OK = 0, 123 | COMPONENT_ERROR, 124 | COMPONENT_TIMEOUT, 125 | COMPONENT_NOT_IMPLEMENTED 126 | } DrvStatusTypeDef; 127 | 128 | /** 129 | * @} 130 | */ 131 | 132 | /** 133 | * @} 134 | */ 135 | 136 | /** 137 | * @} 138 | */ 139 | 140 | /** 141 | * @} 142 | */ 143 | 144 | /** 145 | * @} 146 | */ 147 | 148 | #ifdef __cplusplus 149 | } 150 | #endif 151 | 152 | #endif /* __COMPONENT_H */ 153 | 154 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 155 | -------------------------------------------------------------------------------- /Drivers/BSP/Common/pressure.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file pressure.h 4 | * @author MEMS Application Team 5 | * @version V3.0.0 6 | * @date 12-August-2016 7 | * @brief This header file contains the functions prototypes for the 8 | * pressure driver 9 | ****************************************************************************** 10 | * @attention 11 | * 12 | *

© COPYRIGHT(c) 2016 STMicroelectronics

13 | * 14 | * Redistribution and use in source and binary forms, with or without modification, 15 | * are permitted provided that the following conditions are met: 16 | * 1. Redistributions of source code must retain the above copyright notice, 17 | * this list of conditions and the following disclaimer. 18 | * 2. Redistributions in binary form must reproduce the above copyright notice, 19 | * this list of conditions and the following disclaimer in the documentation 20 | * and/or other materials provided with the distribution. 21 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 22 | * may be used to endorse or promote products derived from this software 23 | * without specific prior written permission. 24 | * 25 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 28 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 29 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 30 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 31 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 32 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 33 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 34 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 35 | * 36 | ****************************************************************************** 37 | */ 38 | 39 | /* Define to prevent recursive inclusion -------------------------------------*/ 40 | #ifndef __PRESSURE_H 41 | #define __PRESSURE_H 42 | 43 | #ifdef __cplusplus 44 | extern "C" { 45 | #endif 46 | 47 | 48 | 49 | /* Includes ------------------------------------------------------------------*/ 50 | #include "sensor.h" 51 | 52 | /** @addtogroup BSP BSP 53 | * @{ 54 | */ 55 | 56 | /** @addtogroup COMPONENTS COMPONENTS 57 | * @{ 58 | */ 59 | 60 | /** @addtogroup COMMON COMMON 61 | * @{ 62 | */ 63 | 64 | /** @addtogroup PRESSURE PRESSURE 65 | * @{ 66 | */ 67 | 68 | /** @addtogroup PRESSURE_Public_Types PRESSURE Public types 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @brief PRESSURE driver structure definition 74 | */ 75 | typedef struct 76 | { 77 | DrvStatusTypeDef ( *Init ) ( DrvContextTypeDef* ); 78 | DrvStatusTypeDef ( *DeInit ) ( DrvContextTypeDef* ); 79 | DrvStatusTypeDef ( *Sensor_Enable ) ( DrvContextTypeDef* ); 80 | DrvStatusTypeDef ( *Sensor_Disable ) ( DrvContextTypeDef* ); 81 | DrvStatusTypeDef ( *Get_WhoAmI ) ( DrvContextTypeDef*, uint8_t* ); 82 | DrvStatusTypeDef ( *Check_WhoAmI ) ( DrvContextTypeDef* ); 83 | DrvStatusTypeDef ( *Get_Press ) ( DrvContextTypeDef*, float* ); 84 | DrvStatusTypeDef ( *Get_ODR ) ( DrvContextTypeDef*, float* ); 85 | DrvStatusTypeDef ( *Set_ODR ) ( DrvContextTypeDef*, SensorOdr_t ); 86 | DrvStatusTypeDef ( *Set_ODR_Value ) ( DrvContextTypeDef*, float ); 87 | DrvStatusTypeDef ( *Read_Reg ) ( DrvContextTypeDef*, uint8_t, uint8_t* ); 88 | DrvStatusTypeDef ( *Write_Reg ) ( DrvContextTypeDef*, uint8_t, uint8_t ); 89 | DrvStatusTypeDef ( *Get_DRDY_Status ) ( DrvContextTypeDef*, uint8_t* ); 90 | } PRESSURE_Drv_t; 91 | 92 | /** 93 | * @brief PRESSURE data structure definition 94 | */ 95 | typedef struct 96 | { 97 | void *pComponentData; /* Component specific data. */ 98 | void *pExtData; /* Other data. */ 99 | } PRESSURE_Data_t; 100 | 101 | /** 102 | * @} 103 | */ 104 | 105 | /** 106 | * @} 107 | */ 108 | 109 | /** 110 | * @} 111 | */ 112 | 113 | /** 114 | * @} 115 | */ 116 | 117 | /** 118 | * @} 119 | */ 120 | 121 | #ifdef __cplusplus 122 | } 123 | #endif 124 | 125 | #endif /* __PRESSURE_H */ 126 | 127 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 128 | -------------------------------------------------------------------------------- /Drivers/BSP/Common/sensor.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file sensor.h 4 | * @author MEMS Application Team 5 | * @version V3.0.0 6 | * @date 12-August-2016 7 | * @brief This header file contains the functions prototypes common for all 8 | * sensor drivers 9 | ****************************************************************************** 10 | * @attention 11 | * 12 | *

© COPYRIGHT(c) 2016 STMicroelectronics

13 | * 14 | * Redistribution and use in source and binary forms, with or without modification, 15 | * are permitted provided that the following conditions are met: 16 | * 1. Redistributions of source code must retain the above copyright notice, 17 | * this list of conditions and the following disclaimer. 18 | * 2. Redistributions in binary form must reproduce the above copyright notice, 19 | * this list of conditions and the following disclaimer in the documentation 20 | * and/or other materials provided with the distribution. 21 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 22 | * may be used to endorse or promote products derived from this software 23 | * without specific prior written permission. 24 | * 25 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 28 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 29 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 30 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 31 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 32 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 33 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 34 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 35 | * 36 | ****************************************************************************** 37 | */ 38 | 39 | /* Define to prevent recursive inclusion -------------------------------------*/ 40 | #ifndef __SENSOR_H 41 | #define __SENSOR_H 42 | 43 | #ifdef __cplusplus 44 | extern "C" { 45 | #endif 46 | 47 | 48 | 49 | /* Includes ------------------------------------------------------------------*/ 50 | 51 | #include 52 | #include "component.h" 53 | 54 | /** @addtogroup BSP BSP 55 | * @{ 56 | */ 57 | 58 | /** @addtogroup COMPONENTS COMPONENTS 59 | * @{ 60 | */ 61 | 62 | /** @addtogroup COMMON COMMON 63 | * @{ 64 | */ 65 | 66 | /** @addtogroup SENSOR SENSOR 67 | * @{ 68 | */ 69 | 70 | /** @addtogroup SENSOR_Public_Types SENSOR Public types 71 | * @{ 72 | */ 73 | 74 | /** 75 | * @brief Sensor axes raw data structure definition 76 | */ 77 | typedef struct 78 | { 79 | int16_t AXIS_X; 80 | int16_t AXIS_Y; 81 | int16_t AXIS_Z; 82 | } SensorAxesRaw_t; 83 | 84 | /** 85 | * @brief Sensor axes data structure definition 86 | */ 87 | typedef struct 88 | { 89 | int32_t AXIS_X; 90 | int32_t AXIS_Y; 91 | int32_t AXIS_Z; 92 | } SensorAxes_t; 93 | 94 | /** 95 | * @brief Sensor output data rate enumerator definition 96 | */ 97 | typedef enum 98 | { 99 | ODR_LOW, 100 | ODR_MID_LOW, 101 | ODR_MID, 102 | ODR_MID_HIGH, 103 | ODR_HIGH 104 | } SensorOdr_t; 105 | 106 | /** 107 | * @brief Sensor full scale enumerator definition 108 | */ 109 | typedef enum 110 | { 111 | FS_LOW, 112 | FS_MID_LOW, 113 | FS_MID, 114 | FS_MID_HIGH, 115 | FS_HIGH 116 | } SensorFs_t; 117 | 118 | /** 119 | * @brief Sensor interrupt pin enumerator definition 120 | */ 121 | typedef enum 122 | { 123 | INT1_PIN, 124 | INT2_PIN 125 | } SensorIntPin_t; 126 | 127 | /** 128 | * @} 129 | */ 130 | 131 | /** 132 | * @} 133 | */ 134 | 135 | /** 136 | * @} 137 | */ 138 | 139 | /** 140 | * @} 141 | */ 142 | 143 | /** 144 | * @} 145 | */ 146 | 147 | #ifdef __cplusplus 148 | } 149 | #endif 150 | 151 | #endif /* __SENSOR_H */ 152 | 153 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 154 | -------------------------------------------------------------------------------- /Drivers/BSP/lsm303agr/LSM303AGR_Combo_driver_HL.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file LSM303AGR_Combo_driver_HL.h 4 | * @author MEMS Application Team 5 | * @version V3.0.0 6 | * @date 27-January-2016 7 | * @brief This file contains definitions for the LSM303AGR combo driver 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT(c) 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without modification, 14 | * are permitted provided that the following conditions are met: 15 | * 1. Redistributions of source code must retain the above copyright notice, 16 | * this list of conditions and the following disclaimer. 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 21 | * may be used to endorse or promote products derived from this software 22 | * without specific prior written permission. 23 | * 24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************** 36 | */ 37 | 38 | /* Define to prevent recursive inclusion -------------------------------------*/ 39 | #ifndef __LSM303AGR_COMBO_DRIVER_HL_H 40 | #define __LSM303AGR_COMBO_DRIVER_HL_H 41 | 42 | #ifdef __cplusplus 43 | extern "C" { 44 | #endif 45 | 46 | 47 | /** @addtogroup BSP BSP 48 | * @{ 49 | */ 50 | 51 | /** @addtogroup COMPONENTS COMPONENTS 52 | * @{ 53 | */ 54 | 55 | /** @addtogroup LSM303AGR_COMBO LSM303AGR_COMBO 56 | * @{ 57 | */ 58 | 59 | /** @addtogroup LSM303AGR_COMBO_Public_Constants Public constants 60 | * @{ 61 | */ 62 | #define LSM303AGR_SENSORS_MAX_NUM 1 /**< LSM303AGR max number of instances */ 63 | 64 | /** 65 | * @} 66 | */ 67 | 68 | /** @addtogroup LSM303AGR_COMBO_Public_Types LSM303AGR_COMBO Public Types 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @brief LSM303AGR combo specific data internal structure definition 74 | */ 75 | typedef struct 76 | { 77 | uint8_t isAccInitialized; 78 | uint8_t isMagInitialized; 79 | } LSM303AGR_Combo_Data_t; 80 | 81 | /** 82 | * @} 83 | */ 84 | 85 | /** @addtogroup LSM303AGR_COMBO_Public_Variables Public variables 86 | * @{ 87 | */ 88 | 89 | extern LSM303AGR_Combo_Data_t LSM303AGR_Combo_Data[LSM303AGR_SENSORS_MAX_NUM]; 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | /** 96 | * @} 97 | */ 98 | 99 | /** 100 | * @} 101 | */ 102 | 103 | /** 104 | * @} 105 | */ 106 | 107 | #ifdef __cplusplus 108 | } 109 | #endif 110 | 111 | #endif /* __LSM303AGR_COMBO_DRIVER_HL_H */ 112 | 113 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 114 | -------------------------------------------------------------------------------- /Drivers/BSP/lsm303agr/LSM303AGR_MAG_driver_HL.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file LSM303AGR_MAG_driver_HL.h 4 | * @author MEMS Application Team 5 | * @version V3.0.0 6 | * @date 12-August-2016 7 | * @brief This file contains definitions for the LSM303AGR_MAG_driver_HL.c firmware driver 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT(c) 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without modification, 14 | * are permitted provided that the following conditions are met: 15 | * 1. Redistributions of source code must retain the above copyright notice, 16 | * this list of conditions and the following disclaimer. 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 21 | * may be used to endorse or promote products derived from this software 22 | * without specific prior written permission. 23 | * 24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************** 36 | */ 37 | 38 | /* Define to prevent recursive inclusion -------------------------------------*/ 39 | #ifndef __LSM303AGR_MAG_DRIVER_HL_H 40 | #define __LSM303AGR_MAG_DRIVER_HL_H 41 | 42 | #ifdef __cplusplus 43 | extern "C" { 44 | #endif 45 | 46 | 47 | 48 | /* Includes ------------------------------------------------------------------*/ 49 | #include "magnetometer.h" 50 | 51 | /* Include magnetic sensor component drivers. */ 52 | #include "LSM303AGR_MAG_driver.h" 53 | #include "LSM303AGR_Combo_driver_HL.h" 54 | 55 | 56 | /** @addtogroup BSP BSP 57 | * @{ 58 | */ 59 | 60 | /** @addtogroup COMPONENTS COMPONENTS 61 | * @{ 62 | */ 63 | 64 | /** @addtogroup LSM303AGR_MAG LSM303AGR_MAG 65 | * @{ 66 | */ 67 | 68 | /** @addtogroup LSM303AGR_MAG_Public_Constants Public constants 69 | * @{ 70 | */ 71 | 72 | /** @addtogroup LSM303AGR_MAG_SENSITIVITY Sensitivity values based on selected full scale 73 | * @{ 74 | */ 75 | 76 | #define LSM303AGR_MAG_SENSITIVITY_FOR_FS_4G 0.14 /**< Sensitivity value for 4 gauss full scale [LSB/gauss] */ 77 | #define LSM303AGR_MAG_SENSITIVITY_FOR_FS_8G 0.29 /**< Sensitivity value for 8 gauss full scale [LSB/gauss] */ 78 | #define LSM303AGR_MAG_SENSITIVITY_FOR_FS_12G 0.43 /**< Sensitivity value for 12 gauss full scale [LSB/gauss] */ 79 | #define LSM303AGR_MAG_SENSITIVITY_FOR_FS_16G 0.58 /**< Sensitivity value for 16 gauss full scale [LSB/gauss] */ 80 | 81 | /** 82 | * @} 83 | */ 84 | 85 | /** 86 | * @} 87 | */ 88 | 89 | /** @addtogroup LSM303AGR_MAG_Public_Types LSM303AGR_MAG Public Types 90 | * @{ 91 | */ 92 | 93 | /** 94 | * @brief LSM303AGR_MAG magneto specific data internal structure definition 95 | */ 96 | 97 | typedef struct 98 | { 99 | LSM303AGR_Combo_Data_t *comboData; /* Combo data to manage in software SPI 3-Wire initialization of the combo sensors */ 100 | } LSM303AGR_M_Data_t; 101 | 102 | /** 103 | * @} 104 | */ 105 | 106 | /** @addtogroup LSM303AGR_MAG_Public_Variables Public variables 107 | * @{ 108 | */ 109 | 110 | extern MAGNETO_Drv_t LSM303AGR_M_Drv; 111 | 112 | /** 113 | * @} 114 | */ 115 | 116 | /** 117 | * @} 118 | */ 119 | 120 | /** 121 | * @} 122 | */ 123 | 124 | /** 125 | * @} 126 | */ 127 | 128 | #ifdef __cplusplus 129 | } 130 | #endif 131 | 132 | #endif /* __LSM303AGR_MAG_DRIVER_HL_H */ 133 | 134 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 135 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f767xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f767xx.h -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Drivers/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F7xx/Include/system_stm32f7xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32f7xx.h 4 | * @author MCD Application Team 5 | * @version V1.2.0 6 | * @date 30-December-2016 7 | * @brief CMSIS Cortex-M7 Device System Source File for STM32F7xx devices. 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT(c) 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without modification, 14 | * are permitted provided that the following conditions are met: 15 | * 1. Redistributions of source code must retain the above copyright notice, 16 | * this list of conditions and the following disclaimer. 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 21 | * may be used to endorse or promote products derived from this software 22 | * without specific prior written permission. 23 | * 24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************** 36 | */ 37 | 38 | /** @addtogroup CMSIS 39 | * @{ 40 | */ 41 | 42 | /** @addtogroup stm32f7xx_system 43 | * @{ 44 | */ 45 | 46 | /** 47 | * @brief Define to prevent recursive inclusion 48 | */ 49 | #ifndef __SYSTEM_STM32F7XX_H 50 | #define __SYSTEM_STM32F7XX_H 51 | 52 | #ifdef __cplusplus 53 | extern "C" { 54 | #endif 55 | 56 | /** @addtogroup STM32F7xx_System_Includes 57 | * @{ 58 | */ 59 | 60 | /** 61 | * @} 62 | */ 63 | 64 | 65 | /** @addtogroup STM32F7xx_System_Exported_Variables 66 | * @{ 67 | */ 68 | /* The SystemCoreClock variable is updated in three ways: 69 | 1) by calling CMSIS function SystemCoreClockUpdate() 70 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq() 71 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency 72 | Note: If you use this function to configure the system clock; then there 73 | is no need to call the 2 first functions listed above, since SystemCoreClock 74 | variable is updated automatically. 75 | */ 76 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ 77 | 78 | extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ 79 | extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ 80 | 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /** @addtogroup STM32F7xx_System_Exported_Constants 87 | * @{ 88 | */ 89 | 90 | /** 91 | * @} 92 | */ 93 | 94 | /** @addtogroup STM32F7xx_System_Exported_Macros 95 | * @{ 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /** @addtogroup STM32F7xx_System_Exported_Functions 103 | * @{ 104 | */ 105 | 106 | extern void SystemInit(void); 107 | extern void SystemCoreClockUpdate(void); 108 | /** 109 | * @} 110 | */ 111 | 112 | #ifdef __cplusplus 113 | } 114 | #endif 115 | 116 | #endif /*__SYSTEM_STM32F7XX_H */ 117 | 118 | /** 119 | * @} 120 | */ 121 | 122 | /** 123 | * @} 124 | */ 125 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 126 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Include/arm_const_structs.h: -------------------------------------------------------------------------------- 1 | /* ---------------------------------------------------------------------- 2 | * Copyright (C) 2010-2014 ARM Limited. All rights reserved. 3 | * 4 | * $Date: 19. March 2015 5 | * $Revision: V.1.4.5 6 | * 7 | * Project: CMSIS DSP Library 8 | * Title: arm_const_structs.h 9 | * 10 | * Description: This file has constant structs that are initialized for 11 | * user convenience. For example, some can be given as 12 | * arguments to the arm_cfft_f32() function. 13 | * 14 | * Target Processor: Cortex-M4/Cortex-M3 15 | * 16 | * Redistribution and use in source and binary forms, with or without 17 | * modification, are permitted provided that the following conditions 18 | * are met: 19 | * - Redistributions of source code must retain the above copyright 20 | * notice, this list of conditions and the following disclaimer. 21 | * - Redistributions in binary form must reproduce the above copyright 22 | * notice, this list of conditions and the following disclaimer in 23 | * the documentation and/or other materials provided with the 24 | * distribution. 25 | * - Neither the name of ARM LIMITED nor the names of its contributors 26 | * may be used to endorse or promote products derived from this 27 | * software without specific prior written permission. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 30 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 32 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 33 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 35 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 36 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 38 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 39 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 40 | * POSSIBILITY OF SUCH DAMAGE. 41 | * -------------------------------------------------------------------- */ 42 | 43 | #ifndef _ARM_CONST_STRUCTS_H 44 | #define _ARM_CONST_STRUCTS_H 45 | 46 | #include "arm_math.h" 47 | #include "arm_common_tables.h" 48 | 49 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16; 50 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32; 51 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64; 52 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128; 53 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256; 54 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512; 55 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024; 56 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048; 57 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096; 58 | 59 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16; 60 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32; 61 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64; 62 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128; 63 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256; 64 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512; 65 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024; 66 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048; 67 | extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096; 68 | 69 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16; 70 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32; 71 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64; 72 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128; 73 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256; 74 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512; 75 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024; 76 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048; 77 | extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096; 78 | 79 | #endif 80 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Include/core_cmFunc.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cmFunc.h 3 | * @brief CMSIS Cortex-M Core Function Access Header File 4 | * @version V4.30 5 | * @date 20. October 2015 6 | ******************************************************************************/ 7 | /* Copyright (c) 2009 - 2015 ARM LIMITED 8 | 9 | All rights reserved. 10 | Redistribution and use in source and binary forms, with or without 11 | modification, are permitted provided that the following conditions are met: 12 | - Redistributions of source code must retain the above copyright 13 | notice, this list of conditions and the following disclaimer. 14 | - Redistributions in binary form must reproduce the above copyright 15 | notice, this list of conditions and the following disclaimer in the 16 | documentation and/or other materials provided with the distribution. 17 | - Neither the name of ARM nor the names of its contributors may be used 18 | to endorse or promote products derived from this software without 19 | specific prior written permission. 20 | * 21 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE 25 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | POSSIBILITY OF SUCH DAMAGE. 32 | ---------------------------------------------------------------------------*/ 33 | 34 | 35 | #if defined ( __ICCARM__ ) 36 | #pragma system_include /* treat file as system include file for MISRA check */ 37 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 38 | #pragma clang system_header /* treat file as system include file */ 39 | #endif 40 | 41 | #ifndef __CORE_CMFUNC_H 42 | #define __CORE_CMFUNC_H 43 | 44 | 45 | /* ########################### Core Function Access ########################### */ 46 | /** \ingroup CMSIS_Core_FunctionInterface 47 | \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions 48 | @{ 49 | */ 50 | 51 | /*------------------ RealView Compiler -----------------*/ 52 | #if defined ( __CC_ARM ) 53 | #include "cmsis_armcc.h" 54 | 55 | /*------------------ ARM Compiler V6 -------------------*/ 56 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 57 | #include "cmsis_armcc_V6.h" 58 | 59 | /*------------------ GNU Compiler ----------------------*/ 60 | #elif defined ( __GNUC__ ) 61 | #include "cmsis_gcc.h" 62 | 63 | /*------------------ ICC Compiler ----------------------*/ 64 | #elif defined ( __ICCARM__ ) 65 | #include 66 | 67 | /*------------------ TI CCS Compiler -------------------*/ 68 | #elif defined ( __TMS470__ ) 69 | #include 70 | 71 | /*------------------ TASKING Compiler ------------------*/ 72 | #elif defined ( __TASKING__ ) 73 | /* 74 | * The CMSIS functions have been implemented as intrinsics in the compiler. 75 | * Please use "carm -?i" to get an up to date list of all intrinsics, 76 | * Including the CMSIS ones. 77 | */ 78 | 79 | /*------------------ COSMIC Compiler -------------------*/ 80 | #elif defined ( __CSMC__ ) 81 | #include 82 | 83 | #endif 84 | 85 | /*@} end of CMSIS_Core_RegAccFunctions */ 86 | 87 | #endif /* __CORE_CMFUNC_H */ 88 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Include/core_cmInstr.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cmInstr.h 3 | * @brief CMSIS Cortex-M Core Instruction Access Header File 4 | * @version V4.30 5 | * @date 20. October 2015 6 | ******************************************************************************/ 7 | /* Copyright (c) 2009 - 2015 ARM LIMITED 8 | 9 | All rights reserved. 10 | Redistribution and use in source and binary forms, with or without 11 | modification, are permitted provided that the following conditions are met: 12 | - Redistributions of source code must retain the above copyright 13 | notice, this list of conditions and the following disclaimer. 14 | - Redistributions in binary form must reproduce the above copyright 15 | notice, this list of conditions and the following disclaimer in the 16 | documentation and/or other materials provided with the distribution. 17 | - Neither the name of ARM nor the names of its contributors may be used 18 | to endorse or promote products derived from this software without 19 | specific prior written permission. 20 | * 21 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE 25 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | POSSIBILITY OF SUCH DAMAGE. 32 | ---------------------------------------------------------------------------*/ 33 | 34 | 35 | #if defined ( __ICCARM__ ) 36 | #pragma system_include /* treat file as system include file for MISRA check */ 37 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 38 | #pragma clang system_header /* treat file as system include file */ 39 | #endif 40 | 41 | #ifndef __CORE_CMINSTR_H 42 | #define __CORE_CMINSTR_H 43 | 44 | 45 | /* ########################## Core Instruction Access ######################### */ 46 | /** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface 47 | Access to dedicated instructions 48 | @{ 49 | */ 50 | 51 | /*------------------ RealView Compiler -----------------*/ 52 | #if defined ( __CC_ARM ) 53 | #include "cmsis_armcc.h" 54 | 55 | /*------------------ ARM Compiler V6 -------------------*/ 56 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 57 | #include "cmsis_armcc_V6.h" 58 | 59 | /*------------------ GNU Compiler ----------------------*/ 60 | #elif defined ( __GNUC__ ) 61 | #include "cmsis_gcc.h" 62 | 63 | /*------------------ ICC Compiler ----------------------*/ 64 | #elif defined ( __ICCARM__ ) 65 | #include 66 | 67 | /*------------------ TI CCS Compiler -------------------*/ 68 | #elif defined ( __TMS470__ ) 69 | #include 70 | 71 | /*------------------ TASKING Compiler ------------------*/ 72 | #elif defined ( __TASKING__ ) 73 | /* 74 | * The CMSIS functions have been implemented as intrinsics in the compiler. 75 | * Please use "carm -?i" to get an up to date list of all intrinsics, 76 | * Including the CMSIS ones. 77 | */ 78 | 79 | /*------------------ COSMIC Compiler -------------------*/ 80 | #elif defined ( __CSMC__ ) 81 | #include 82 | 83 | #endif 84 | 85 | /*@}*/ /* end of group CMSIS_Core_InstructionInterface */ 86 | 87 | #endif /* __CORE_CMINSTR_H */ 88 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Include/core_cmSimd.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file core_cmSimd.h 3 | * @brief CMSIS Cortex-M SIMD Header File 4 | * @version V4.30 5 | * @date 20. October 2015 6 | ******************************************************************************/ 7 | /* Copyright (c) 2009 - 2015 ARM LIMITED 8 | 9 | All rights reserved. 10 | Redistribution and use in source and binary forms, with or without 11 | modification, are permitted provided that the following conditions are met: 12 | - Redistributions of source code must retain the above copyright 13 | notice, this list of conditions and the following disclaimer. 14 | - Redistributions in binary form must reproduce the above copyright 15 | notice, this list of conditions and the following disclaimer in the 16 | documentation and/or other materials provided with the distribution. 17 | - Neither the name of ARM nor the names of its contributors may be used 18 | to endorse or promote products derived from this software without 19 | specific prior written permission. 20 | * 21 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE 25 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | POSSIBILITY OF SUCH DAMAGE. 32 | ---------------------------------------------------------------------------*/ 33 | 34 | 35 | #if defined ( __ICCARM__ ) 36 | #pragma system_include /* treat file as system include file for MISRA check */ 37 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 38 | #pragma clang system_header /* treat file as system include file */ 39 | #endif 40 | 41 | #ifndef __CORE_CMSIMD_H 42 | #define __CORE_CMSIMD_H 43 | 44 | #ifdef __cplusplus 45 | extern "C" { 46 | #endif 47 | 48 | 49 | /* ################### Compiler specific Intrinsics ########################### */ 50 | /** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics 51 | Access to dedicated SIMD instructions 52 | @{ 53 | */ 54 | 55 | /*------------------ RealView Compiler -----------------*/ 56 | #if defined ( __CC_ARM ) 57 | #include "cmsis_armcc.h" 58 | 59 | /*------------------ ARM Compiler V6 -------------------*/ 60 | #elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) 61 | #include "cmsis_armcc_V6.h" 62 | 63 | /*------------------ GNU Compiler ----------------------*/ 64 | #elif defined ( __GNUC__ ) 65 | #include "cmsis_gcc.h" 66 | 67 | /*------------------ ICC Compiler ----------------------*/ 68 | #elif defined ( __ICCARM__ ) 69 | #include 70 | 71 | /*------------------ TI CCS Compiler -------------------*/ 72 | #elif defined ( __TMS470__ ) 73 | #include 74 | 75 | /*------------------ TASKING Compiler ------------------*/ 76 | #elif defined ( __TASKING__ ) 77 | /* 78 | * The CMSIS functions have been implemented as intrinsics in the compiler. 79 | * Please use "carm -?i" to get an up to date list of all intrinsics, 80 | * Including the CMSIS ones. 81 | */ 82 | 83 | /*------------------ COSMIC Compiler -------------------*/ 84 | #elif defined ( __CSMC__ ) 85 | #include 86 | 87 | #endif 88 | 89 | /*@} end of group CMSIS_SIMD_intrinsics */ 90 | 91 | 92 | #ifdef __cplusplus 93 | } 94 | #endif 95 | 96 | #endif /* __CORE_CMSIMD_H */ 97 | -------------------------------------------------------------------------------- /Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_pcd_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f7xx_hal_pcd_ex.h 4 | * @author MCD Application Team 5 | * @version V1.2.0 6 | * @date 30-December-2016 7 | * @brief Header file of PCD HAL module. 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT(c) 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without modification, 14 | * are permitted provided that the following conditions are met: 15 | * 1. Redistributions of source code must retain the above copyright notice, 16 | * this list of conditions and the following disclaimer. 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 21 | * may be used to endorse or promote products derived from this software 22 | * without specific prior written permission. 23 | * 24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************** 36 | */ 37 | 38 | /* Define to prevent recursive inclusion -------------------------------------*/ 39 | #ifndef __STM32F7xx_HAL_PCD_EX_H 40 | #define __STM32F7xx_HAL_PCD_EX_H 41 | 42 | #ifdef __cplusplus 43 | extern "C" { 44 | #endif 45 | 46 | /* Includes ------------------------------------------------------------------*/ 47 | #include "stm32f7xx_hal_def.h" 48 | 49 | /** @addtogroup STM32F7xx_HAL_Driver 50 | * @{ 51 | */ 52 | 53 | /** @addtogroup PCDEx 54 | * @{ 55 | */ 56 | /* Exported types ------------------------------------------------------------*/ 57 | typedef enum 58 | { 59 | PCD_LPM_L0_ACTIVE = 0x00U, /* on */ 60 | PCD_LPM_L1_ACTIVE = 0x01U, /* LPM L1 sleep */ 61 | }PCD_LPM_MsgTypeDef; 62 | 63 | typedef enum 64 | { 65 | PCD_BCD_ERROR = 0xFF, 66 | PCD_BCD_CONTACT_DETECTION = 0xFE, 67 | PCD_BCD_STD_DOWNSTREAM_PORT = 0xFD, 68 | PCD_BCD_CHARGING_DOWNSTREAM_PORT = 0xFC, 69 | PCD_BCD_DEDICATED_CHARGING_PORT = 0xFB, 70 | PCD_BCD_DISCOVERY_COMPLETED = 0x00, 71 | 72 | }PCD_BCD_MsgTypeDef; 73 | 74 | /* Exported constants --------------------------------------------------------*/ 75 | /* Exported macros -----------------------------------------------------------*/ 76 | /* Exported functions --------------------------------------------------------*/ 77 | /** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions 78 | * @{ 79 | */ 80 | /** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions 81 | * @{ 82 | */ 83 | HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); 84 | HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); 85 | HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); 86 | HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); 87 | HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); 88 | HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); 89 | void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); 90 | void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); 91 | void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); 92 | 93 | /** 94 | * @} 95 | */ 96 | 97 | /** 98 | * @} 99 | */ 100 | 101 | /** 102 | * @} 103 | */ 104 | 105 | /** 106 | * @} 107 | */ 108 | 109 | #ifdef __cplusplus 110 | } 111 | #endif 112 | 113 | 114 | #endif /* __STM32F7xx_HAL_PCD_EX_H */ 115 | 116 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 117 | -------------------------------------------------------------------------------- /Drivers/STM32F7xx_HAL_Driver/Inc/stm32f7xx_hal_sai_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f7xx_hal_sai_ex.h 4 | * @author MCD Application Team 5 | * @version V1.2.0 6 | * @date 30-December-2016 7 | * @brief Header file of SAI Extension HAL module. 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT(c) 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without modification, 14 | * are permitted provided that the following conditions are met: 15 | * 1. Redistributions of source code must retain the above copyright notice, 16 | * this list of conditions and the following disclaimer. 17 | * 2. Redistributions in binary form must reproduce the above copyright notice, 18 | * this list of conditions and the following disclaimer in the documentation 19 | * and/or other materials provided with the distribution. 20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 21 | * may be used to endorse or promote products derived from this software 22 | * without specific prior written permission. 23 | * 24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************** 36 | */ 37 | 38 | /* Define to prevent recursive inclusion -------------------------------------*/ 39 | #ifndef __STM32F7xx_HAL_SAI_EX_H 40 | #define __STM32F7xx_HAL_SAI_EX_H 41 | 42 | 43 | /* Includes ------------------------------------------------------------------*/ 44 | /* Exported types ------------------------------------------------------------*/ 45 | /* Exported constants --------------------------------------------------------*/ 46 | /* Exported functions --------------------------------------------------------*/ 47 | /* Extended features functions ************************************************/ 48 | /* Private types -------------------------------------------------------------*/ 49 | /* Private variables ---------------------------------------------------------*/ 50 | /* Private constants ---------------------------------------------------------*/ 51 | /* Private macros ------------------------------------------------------------*/ 52 | /* Private functions ---------------------------------------------------------*/ 53 | 54 | #endif /* __STM32F7xx_HAL_SAI_EX_H */ 55 | 56 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 57 | -------------------------------------------------------------------------------- /Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sai_ex.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f7xx_hal_sai_ex.c 4 | * @author MCD Application Team 5 | * @version V1.2.0 6 | * @date 30-December-2016 7 | * @brief Empty file; This file is no longer used to set synchronization and 8 | * to get SAI block frequency. Its content is now moved to common files 9 | * (stm32f7xx_hal_sai.c/.h) as there's no device's dependency within F7 10 | * family. It's just kept for compatibility reasons. 11 | * 12 | ****************************************************************************** 13 | * @attention 14 | * 15 | *

© COPYRIGHT(c) 2016 STMicroelectronics

16 | * 17 | * Redistribution and use in source and binary forms, with or without modification, 18 | * are permitted provided that the following conditions are met: 19 | * 1. Redistributions of source code must retain the above copyright notice, 20 | * this list of conditions and the following disclaimer. 21 | * 2. Redistributions in binary form must reproduce the above copyright notice, 22 | * this list of conditions and the following disclaimer in the documentation 23 | * and/or other materials provided with the distribution. 24 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 25 | * may be used to endorse or promote products derived from this software 26 | * without specific prior written permission. 27 | * 28 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 29 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 30 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 31 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 32 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 33 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 34 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 35 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 36 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 37 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 38 | * 39 | ****************************************************************************** 40 | */ 41 | 42 | /* Includes ------------------------------------------------------------------*/ 43 | #include "stm32f7xx_hal.h" 44 | /* Private typedef -----------------------------------------------------------*/ 45 | /* Private define ------------------------------------------------------------*/ 46 | /* Private macro -------------------------------------------------------------*/ 47 | /* Private variables ---------------------------------------------------------*/ 48 | /* Private function prototypes -----------------------------------------------*/ 49 | /* Private functions ---------------------------------------------------------*/ 50 | 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c -------------------------------------------------------------------------------- /Drivers/gpio.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : gpio.c 4 | * Description : This file provides code for the configuration 5 | * of all used GPIO pins. 6 | ****************************************************************************** 7 | * 8 | * COPYRIGHT(c) 2017 STMicroelectronics 9 | * 10 | * Redistribution and use in source and binary forms, with or without modification, 11 | * are permitted provided that the following conditions are met: 12 | * 1. Redistributions of source code must retain the above copyright notice, 13 | * this list of conditions and the following disclaimer. 14 | * 2. Redistributions in binary form must reproduce the above copyright notice, 15 | * this list of conditions and the following disclaimer in the documentation 16 | * and/or other materials provided with the distribution. 17 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 18 | * may be used to endorse or promote products derived from this software 19 | * without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 24 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 25 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 26 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 27 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 28 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 29 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 30 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 31 | * 32 | ****************************************************************************** 33 | */ 34 | 35 | /* Includes ------------------------------------------------------------------*/ 36 | #include "gpio.h" 37 | /* USER CODE BEGIN 0 */ 38 | 39 | /* USER CODE END 0 */ 40 | 41 | /*----------------------------------------------------------------------------*/ 42 | /* Configure GPIO */ 43 | /*----------------------------------------------------------------------------*/ 44 | /* USER CODE BEGIN 1 */ 45 | 46 | /* USER CODE END 1 */ 47 | 48 | /** Configure pins as 49 | * Analog 50 | * Input 51 | * Output 52 | * EVENT_OUT 53 | * EXTI 54 | */ 55 | void MX_GPIO_Init(void) 56 | { 57 | GPIO_InitTypeDef GPIO_InitStruct; 58 | /* GPIO Ports Clock Enable */ 59 | __HAL_RCC_GPIOH_CLK_ENABLE(); 60 | __HAL_RCC_GPIOD_CLK_ENABLE(); 61 | __HAL_RCC_GPIOA_CLK_ENABLE(); 62 | __HAL_RCC_GPIOB_CLK_ENABLE(); 63 | 64 | GPIO_InitStruct.Pin = GPIO_PIN_14; 65 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 66 | GPIO_InitStruct.Pull = GPIO_NOPULL; 67 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; 68 | 69 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 70 | HAL_GPIO_WritePin(GPIOB, GPIO_PIN_14, GPIO_PIN_SET); 71 | 72 | 73 | 74 | } 75 | 76 | /* USER CODE BEGIN 2 */ 77 | 78 | /* USER CODE END 2 */ 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 89 | -------------------------------------------------------------------------------- /Drivers/gpio.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : gpio.h 4 | * Description : This file contains all the functions prototypes for 5 | * the gpio 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | /* Define to prevent recursive inclusion -------------------------------------*/ 46 | #ifndef __gpio_H 47 | #define __gpio_H 48 | #ifdef __cplusplus 49 | extern "C" { 50 | #endif 51 | 52 | /* Includes ------------------------------------------------------------------*/ 53 | #include "stm32f7xx_hal.h" 54 | #include "main.h" 55 | 56 | /* USER CODE BEGIN Includes */ 57 | 58 | /* USER CODE END Includes */ 59 | 60 | /* USER CODE BEGIN Private defines */ 61 | 62 | /* USER CODE END Private defines */ 63 | 64 | void MX_GPIO_Init(void); 65 | 66 | /* USER CODE BEGIN Prototypes */ 67 | 68 | /* USER CODE END Prototypes */ 69 | 70 | #ifdef __cplusplus 71 | } 72 | #endif 73 | #endif /*__ pinoutConfig_H */ 74 | 75 | /** 76 | * @} 77 | */ 78 | 79 | /** 80 | * @} 81 | */ 82 | 83 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 84 | -------------------------------------------------------------------------------- /Drivers/stm32f7xx_hal_msp.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : stm32f7xx_hal_msp.c 4 | * Description : This file provides code for the MSP Initialization 5 | * and de-Initialization codes. 6 | ****************************************************************************** 7 | * 8 | * COPYRIGHT(c) 2017 STMicroelectronics 9 | * 10 | * Redistribution and use in source and binary forms, with or without modification, 11 | * are permitted provided that the following conditions are met: 12 | * 1. Redistributions of source code must retain the above copyright notice, 13 | * this list of conditions and the following disclaimer. 14 | * 2. Redistributions in binary form must reproduce the above copyright notice, 15 | * this list of conditions and the following disclaimer in the documentation 16 | * and/or other materials provided with the distribution. 17 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 18 | * may be used to endorse or promote products derived from this software 19 | * without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 24 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 25 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 26 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 27 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 28 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 29 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 30 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 31 | * 32 | ****************************************************************************** 33 | */ 34 | /* Includes ------------------------------------------------------------------*/ 35 | #include "stm32f7xx_hal.h" 36 | 37 | extern void Error_Handler(void); 38 | /* USER CODE BEGIN 0 */ 39 | 40 | /* USER CODE END 0 */ 41 | /** 42 | * Initializes the Global MSP. 43 | */ 44 | void HAL_MspInit(void) 45 | { 46 | /* USER CODE BEGIN MspInit 0 */ 47 | 48 | /* USER CODE END MspInit 0 */ 49 | 50 | HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); 51 | 52 | /* System interrupt init*/ 53 | /* MemoryManagement_IRQn interrupt configuration */ 54 | HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); 55 | /* BusFault_IRQn interrupt configuration */ 56 | HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); 57 | /* UsageFault_IRQn interrupt configuration */ 58 | HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); 59 | /* SVCall_IRQn interrupt configuration */ 60 | HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); 61 | /* DebugMonitor_IRQn interrupt configuration */ 62 | HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); 63 | /* PendSV_IRQn interrupt configuration */ 64 | HAL_NVIC_SetPriority(PendSV_IRQn, 5, 0); 65 | /* SysTick_IRQn interrupt configuration */ 66 | HAL_NVIC_SetPriority(SysTick_IRQn, 5, 0); 67 | 68 | /* USER CODE BEGIN MspInit 1 */ 69 | 70 | /* USER CODE END MspInit 1 */ 71 | } 72 | 73 | /* USER CODE BEGIN 1 */ 74 | 75 | /* USER CODE END 1 */ 76 | 77 | /** 78 | * @} 79 | */ 80 | 81 | /** 82 | * @} 83 | */ 84 | 85 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 86 | -------------------------------------------------------------------------------- /Drivers/stm32f7xx_it.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f7xx_it.h 4 | * @brief This file contains the headers of the interrupt handlers. 5 | ****************************************************************************** 6 | * 7 | * COPYRIGHT(c) 2017 STMicroelectronics 8 | * 9 | * Redistribution and use in source and binary forms, with or without modification, 10 | * are permitted provided that the following conditions are met: 11 | * 1. Redistributions of source code must retain the above copyright notice, 12 | * this list of conditions and the following disclaimer. 13 | * 2. Redistributions in binary form must reproduce the above copyright notice, 14 | * this list of conditions and the following disclaimer in the documentation 15 | * and/or other materials provided with the distribution. 16 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 17 | * may be used to endorse or promote products derived from this software 18 | * without specific prior written permission. 19 | * 20 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | * 31 | ****************************************************************************** 32 | */ 33 | 34 | /* Define to prevent recursive inclusion -------------------------------------*/ 35 | #ifndef __STM32F7xx_IT_H 36 | #define __STM32F7xx_IT_H 37 | 38 | #ifdef __cplusplus 39 | extern "C" { 40 | #endif 41 | 42 | /* Includes ------------------------------------------------------------------*/ 43 | /* Exported types ------------------------------------------------------------*/ 44 | /* Exported constants --------------------------------------------------------*/ 45 | /* Exported macro ------------------------------------------------------------*/ 46 | /* Exported functions ------------------------------------------------------- */ 47 | 48 | void SysTick_Handler(void); 49 | void TIM6_DAC_IRQHandler(void); 50 | void ETH_IRQHandler(void); 51 | void OTG_FS_IRQHandler(void); 52 | 53 | #ifdef __cplusplus 54 | } 55 | #endif 56 | 57 | #endif /* __STM32F7xx_IT_H */ 58 | 59 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 60 | -------------------------------------------------------------------------------- /Drivers/tim.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Drivers/tim.c -------------------------------------------------------------------------------- /Drivers/tim.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : TIM.h 4 | * Description : This file provides code for the configuration 5 | * of the TIM instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __tim_H 46 | #define __tim_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern TIM_HandleTypeDef htim1; 60 | extern TIM_HandleTypeDef htim2; 61 | extern TIM_HandleTypeDef htim3; 62 | extern TIM_HandleTypeDef htim4; 63 | extern TIM_HandleTypeDef htim5; 64 | extern TIM_HandleTypeDef htim6; 65 | extern TIM_HandleTypeDef htim8; 66 | extern TIM_HandleTypeDef htim9; 67 | extern TIM_HandleTypeDef htim10; 68 | extern TIM_HandleTypeDef htim11; 69 | extern TIM_HandleTypeDef htim13; 70 | extern TIM_HandleTypeDef htim14; 71 | 72 | /* USER CODE BEGIN Private defines */ 73 | 74 | /* USER CODE END Private defines */ 75 | 76 | extern void Error_Handler(void); 77 | 78 | void MX_TIM1_Init(void); 79 | void MX_TIM2_Init(void); 80 | void MX_TIM3_Init(void); 81 | void MX_TIM4_Init(void); 82 | void MX_TIM5_Init(void); 83 | void MX_TIM6_Init(void); 84 | void MX_TIM8_Init(void); 85 | void MX_TIM9_Init(void); 86 | void MX_TIM10_Init(void); 87 | void MX_TIM11_Init(void); 88 | void MX_TIM13_Init(void); 89 | void MX_TIM14_Init(void); 90 | 91 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); 92 | 93 | 94 | /* USER CODE BEGIN Prototypes */ 95 | 96 | /* USER CODE END Prototypes */ 97 | 98 | #ifdef __cplusplus 99 | } 100 | #endif 101 | #endif /*__ tim_H */ 102 | 103 | /** 104 | * @} 105 | */ 106 | 107 | /** 108 | * @} 109 | */ 110 | 111 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 112 | -------------------------------------------------------------------------------- /Drivers/usart.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : USART.h 4 | * Description : This file provides code for the configuration 5 | * of the USART instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __usart_H 46 | #define __usart_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | 54 | #include "main.h" 55 | 56 | /* USER CODE BEGIN Includes */ 57 | 58 | /* USER CODE END Includes */ 59 | 60 | extern UART_HandleTypeDef huart5; 61 | extern UART_HandleTypeDef huart7; 62 | extern UART_HandleTypeDef huart8; 63 | extern UART_HandleTypeDef huart3; 64 | #define UART_RxBufferSize 256 65 | /* USER CODE BEGIN Private defines */ 66 | typedef struct { 67 | uint8_t *pDMA_Buffer; 68 | uint16_t StartOfMsg; 69 | } TUart_Engine; 70 | typedef struct { 71 | uint32_t Len; 72 | uint8_t Data[UART_RxBufferSize]; 73 | } TMsg; 74 | /* USER CODE END Private defines */ 75 | 76 | extern void Error_Handler(void); 77 | 78 | void MX_UART5_Init(void); 79 | void MX_UART7_Init(void); 80 | void MX_UART8_Init(void); 81 | void MX_USART3_DMA_Init(void); 82 | void MX_USART3_UART_Init(void); 83 | int UART_ReceivedMSG(TMsg *Msg); 84 | void LL_UART_IRQHandler_UART3(void); 85 | /* USER CODE BEGIN Prototypes */ 86 | 87 | /* USER CODE END Prototypes */ 88 | 89 | #ifdef __cplusplus 90 | } 91 | #endif 92 | #endif /*__ usart_H */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 103 | -------------------------------------------------------------------------------- /EWARM/Project.eww: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | $WS_DIR$\EEDrone.ewp 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /EWARM/stm32f767xx_ITCM_flash.icf: -------------------------------------------------------------------------------- 1 | /*###ICF### Section handled by ICF editor, don't touch! ****/ 2 | /*-Editor annotation file-*/ 3 | /* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ 4 | /*-Specials-*/ 5 | define symbol __ICFEDIT_intvec_start__ = 0x00200000; 6 | /*-Memory Regions-*/ 7 | define symbol __ICFEDIT_region_ROM_start__ = 0x00200000; 8 | define symbol __ICFEDIT_region_ROM_end__ = 0x003FFFFF; 9 | define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; 10 | define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; 11 | define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; 12 | define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; 13 | /*-Sizes-*/ 14 | define symbol __ICFEDIT_size_cstack__ = 0x800; 15 | define symbol __ICFEDIT_size_heap__ = 0x400; 16 | /**** End of ICF editor section. ###ICF###*/ 17 | 18 | 19 | define memory mem with size = 4G; 20 | define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; 21 | define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; 22 | define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; 23 | 24 | define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; 25 | define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; 26 | 27 | initialize by copy { readwrite }; 28 | do not initialize { section .noinit }; 29 | 30 | place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; 31 | 32 | place in ROM_region { readonly }; 33 | place in RAM_region { readwrite, 34 | block CSTACK, block HEAP }; 35 | place in ITCMRAM_region { }; 36 | -------------------------------------------------------------------------------- /EWARM/stm32f767xx_flash.icf: -------------------------------------------------------------------------------- 1 | /*###ICF### Section handled by ICF editor, don't touch! ****/ 2 | /*-Editor annotation file-*/ 3 | /* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ 4 | /*-Specials-*/ 5 | define symbol __ICFEDIT_intvec_start__ = 0x08000000; 6 | /*-Memory Regions-*/ 7 | define symbol __ICFEDIT_region_ROM_start__ = 0x08000000; 8 | define symbol __ICFEDIT_region_ROM_end__ = 0x081FFFFF; 9 | define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; 10 | define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; 11 | define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; 12 | define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; 13 | /*-Sizes-*/ 14 | define symbol __ICFEDIT_size_cstack__ = 0x800; 15 | define symbol __ICFEDIT_size_heap__ = 0x400; 16 | /**** End of ICF editor section. ###ICF###*/ 17 | 18 | 19 | define memory mem with size = 4G; 20 | define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; 21 | define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; 22 | define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; 23 | 24 | define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; 25 | define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; 26 | 27 | initialize by copy { readwrite }; 28 | do not initialize { section .noinit }; 29 | 30 | place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; 31 | 32 | place in ROM_region { readonly }; 33 | place in RAM_region { readwrite, 34 | block CSTACK, block HEAP }; 35 | -------------------------------------------------------------------------------- /EWARM/stm32f767xx_sram.icf: -------------------------------------------------------------------------------- 1 | /*###ICF### Section handled by ICF editor, don't touch! ****/ 2 | /*-Editor annotation file-*/ 3 | /* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ 4 | /*-Specials-*/ 5 | define symbol __ICFEDIT_intvec_start__ = 0x20000000; 6 | /*-Memory Regions-*/ 7 | define symbol __ICFEDIT_region_ROM_start__ = 0x20000000; 8 | define symbol __ICFEDIT_region_ROM_end__ = 0x2004FFFF; 9 | define symbol __ICFEDIT_region_RAM_start__ = 0x20050000; 10 | define symbol __ICFEDIT_region_RAM_end__ = 0x2007FFFF; 11 | define symbol __ICFEDIT_region_ITCMRAM_start__ = 0x00000000; 12 | define symbol __ICFEDIT_region_ITCMRAM_end__ = 0x00003FFF; 13 | /*-Sizes-*/ 14 | define symbol __ICFEDIT_size_cstack__ = 0x800; 15 | define symbol __ICFEDIT_size_heap__ = 0x400; 16 | /**** End of ICF editor section. ###ICF###*/ 17 | 18 | 19 | define memory mem with size = 4G; 20 | define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; 21 | define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; 22 | define region ITCMRAM_region = mem:[from __ICFEDIT_region_ITCMRAM_start__ to __ICFEDIT_region_ITCMRAM_end__]; 23 | 24 | define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; 25 | define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; 26 | 27 | initialize by copy { readwrite }; 28 | do not initialize { section .noinit }; 29 | 30 | place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; 31 | 32 | place in ROM_region { readonly }; 33 | place in RAM_region { readwrite, 34 | block CSTACK, block HEAP }; 35 | -------------------------------------------------------------------------------- /Example/AHRS_Test/system.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Example/AHRS_Test/system.c -------------------------------------------------------------------------------- /Example/AHRS_Test/system.h: -------------------------------------------------------------------------------- 1 | #ifndef __SYSTEM_H__ 2 | #define __SYSTEM_H__ 3 | 4 | #include "stm32f7xx_hal.h" 5 | 6 | 7 | void System_Launch(void); 8 | 9 | typedef enum 10 | { 11 | TARGET_NUCLEO, 12 | TARGET_BLUECOIN, 13 | TARGET_SENSORTILE, 14 | TARGETS_NUMBER 15 | } TargetType_t; 16 | 17 | 18 | typedef struct 19 | { 20 | TargetType_t BoardType; 21 | int32_t NumTempSensors; 22 | 23 | 24 | void *HandlePressSensor; 25 | void *HandleHumSensor; 26 | 27 | int32_t HWAdvanceFeatures; 28 | void *HandleAccSensor; 29 | void *HandleGyroSensor; 30 | void *HandleMagSensor; 31 | 32 | int32_t NumMicSensors; 33 | 34 | uint8_t LedStatus; 35 | uint8_t bnrg_expansion_board; 36 | } TargetFeatures_t; 37 | 38 | #endif //__SYSTEM_H__ 39 | -------------------------------------------------------------------------------- /Example/MavLink_Test/mavlink.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Example/MavLink_Test/mavlink.c -------------------------------------------------------------------------------- /Example/MavLink_Test/system.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Example/MavLink_Test/system.c -------------------------------------------------------------------------------- /Example/MavLink_Test/system.h: -------------------------------------------------------------------------------- 1 | #ifndef __SYSTEM_H__ 2 | #define __SYSTEM_H__ 3 | 4 | #include "stm32f7xx_hal.h" 5 | 6 | 7 | void System_Launch(void); 8 | 9 | typedef enum 10 | { 11 | TARGET_NUCLEO, 12 | TARGET_BLUECOIN, 13 | TARGET_SENSORTILE, 14 | TARGETS_NUMBER 15 | } TargetType_t; 16 | 17 | 18 | typedef struct 19 | { 20 | TargetType_t BoardType; 21 | int32_t NumTempSensors; 22 | 23 | 24 | void *HandlePressSensor; 25 | void *HandleHumSensor; 26 | 27 | int32_t HWAdvanceFeatures; 28 | void *HandleAccSensor; 29 | void *HandleGyroSensor; 30 | void *HandleMagSensor; 31 | 32 | int32_t NumMicSensors; 33 | 34 | uint8_t LedStatus; 35 | uint8_t bnrg_expansion_board; 36 | } TargetFeatures_t; 37 | 38 | 39 | 40 | #endif //__SYSTEM_H__ 41 | -------------------------------------------------------------------------------- /Example/Sensor_Test/system.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Example/Sensor_Test/system.c -------------------------------------------------------------------------------- /Example/Sensor_Test/system.h: -------------------------------------------------------------------------------- 1 | #ifndef __SYSTEM_H__ 2 | #define __SYSTEM_H__ 3 | 4 | #include "stm32f7xx_hal.h" 5 | 6 | 7 | void System_Launch(void); 8 | 9 | typedef enum 10 | { 11 | TARGET_NUCLEO, 12 | TARGET_BLUECOIN, 13 | TARGET_SENSORTILE, 14 | TARGETS_NUMBER 15 | } TargetType_t; 16 | 17 | 18 | typedef struct 19 | { 20 | TargetType_t BoardType; 21 | int32_t NumTempSensors; 22 | 23 | 24 | void *HandlePressSensor; 25 | void *HandleHumSensor; 26 | 27 | int32_t HWAdvanceFeatures; 28 | void *HandleAccSensor; 29 | void *HandleGyroSensor; 30 | void *HandleMagSensor; 31 | 32 | int32_t NumMicSensors; 33 | 34 | uint8_t LedStatus; 35 | uint8_t bnrg_expansion_board; 36 | } TargetFeatures_t; 37 | 38 | 39 | 40 | #endif //__SYSTEM_H__ 41 | -------------------------------------------------------------------------------- /Inc/adc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : ADC.h 4 | * Description : This file provides code for the configuration 5 | * of the ADC instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __adc_H 46 | #define __adc_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern ADC_HandleTypeDef hadc3; 60 | 61 | /* USER CODE BEGIN Private defines */ 62 | 63 | /* USER CODE END Private defines */ 64 | 65 | extern void Error_Handler(void); 66 | 67 | void MX_ADC3_Init(void); 68 | 69 | /* USER CODE BEGIN Prototypes */ 70 | 71 | /* USER CODE END Prototypes */ 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | #endif /*__ adc_H */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 87 | -------------------------------------------------------------------------------- /Inc/can.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : CAN.h 4 | * Description : This file provides code for the configuration 5 | * of the CAN instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __can_H 46 | #define __can_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern CAN_HandleTypeDef hcan1; 60 | 61 | /* USER CODE BEGIN Private defines */ 62 | 63 | /* USER CODE END Private defines */ 64 | 65 | extern void Error_Handler(void); 66 | 67 | void MX_CAN1_Init(void); 68 | 69 | /* USER CODE BEGIN Prototypes */ 70 | 71 | /* USER CODE END Prototypes */ 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | #endif /*__ can_H */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 87 | -------------------------------------------------------------------------------- /Inc/config.h: -------------------------------------------------------------------------------- 1 | #ifndef CONFIG_H_ 2 | #define CONFIG_H_ 3 | // Task names 4 | #define TEST_TASK_NAME "TEST" 5 | #define SYSTEM_TASK_NAME "SYSTEM" 6 | #define INIT_TASK_NAME "INIT" 7 | #define MAIN_TASK_NAME "MAIN" 8 | #define MAVLINK_TASK_NAME "MAVLINK" 9 | // Task priorities. Higher number higher priority 10 | #define TEST_TASK_PRI 2 11 | #define SYSTEM_TASK_PRI 2 12 | #define INIT_TASK_PRI 5 13 | #define MAIN_TASK_PRI 6 14 | #define MAVLINK_TASK_PRI 2 15 | //Task stack sizes 16 | #define TEST_TASK_STACKSIZE configMINIMAL_STACK_SIZE 17 | #define SYSTEM_TASK_STACKSIZE (2* configMINIMAL_STACK_SIZE) 18 | #define INIT_TASK_STACKSIZE (3* configMINIMAL_STACK_SIZE) 19 | #define MAIN_TASK_STACKSIZE (3* configMINIMAL_STACK_SIZE) 20 | #define MAVLINK_TASK_STACKSIZE (3* configMINIMAL_STACK_SIZE) 21 | #endif /* CONFIG_H_ */ 22 | -------------------------------------------------------------------------------- /Inc/eth.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : ETH.h 4 | * Description : This file provides code for the configuration 5 | * of the ETH instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __eth_H 46 | #define __eth_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern ETH_HandleTypeDef heth; 60 | 61 | /* USER CODE BEGIN Private defines */ 62 | 63 | /* USER CODE END Private defines */ 64 | 65 | extern void Error_Handler(void); 66 | 67 | void MX_ETH_Init(void); 68 | 69 | /* USER CODE BEGIN Prototypes */ 70 | 71 | /* USER CODE END Prototypes */ 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | #endif /*__ eth_H */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 87 | -------------------------------------------------------------------------------- /Inc/ethernetif.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : ethernetif.h 4 | * Description : This file provides initialization code for LWIP 5 | * middleWare. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | 46 | #ifndef __ETHERNETIF_H__ 47 | #define __ETHERNETIF_H__ 48 | 49 | #include "lwip/err.h" 50 | #include "lwip/netif.h" 51 | #include "cmsis_os.h" 52 | 53 | /* Within 'USER CODE' section, code will be kept by default at each generation */ 54 | /* USER CODE BEGIN 0 */ 55 | 56 | /* USER CODE END 0 */ 57 | 58 | /* Exported functions ------------------------------------------------------- */ 59 | err_t ethernetif_init(struct netif *netif); 60 | 61 | void ethernetif_input( void const * argument ); 62 | 63 | 64 | void ethernetif_update_config(struct netif *netif); 65 | void ethernetif_notify_conn_changed(struct netif *netif); 66 | 67 | /* USER CODE BEGIN 1 */ 68 | 69 | /* USER CODE END 1 */ 70 | #endif 71 | 72 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 73 | -------------------------------------------------------------------------------- /Inc/fatfs.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file fatfs.h 4 | * @brief Header for fatfs applications 5 | ****************************************************************************** 6 | * 7 | * Copyright (c) 2017 STMicroelectronics International N.V. 8 | * All rights reserved. 9 | * 10 | * Redistribution and use in source and binary forms, with or without 11 | * modification, are permitted, provided that the following conditions are met: 12 | * 13 | * 1. Redistribution of source code must retain the above copyright notice, 14 | * this list of conditions and the following disclaimer. 15 | * 2. Redistributions in binary form must reproduce the above copyright notice, 16 | * this list of conditions and the following disclaimer in the documentation 17 | * and/or other materials provided with the distribution. 18 | * 3. Neither the name of STMicroelectronics nor the names of other 19 | * contributors to this software may be used to endorse or promote products 20 | * derived from this software without specific written permission. 21 | * 4. This software, including modifications and/or derivative works of this 22 | * software, must execute solely and exclusively on microcontroller or 23 | * microprocessor devices manufactured by or for STMicroelectronics. 24 | * 5. Redistribution and use of this software other than as permitted under 25 | * this license is void and will automatically terminate your rights under 26 | * this license. 27 | * 28 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 29 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 30 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 31 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 32 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 33 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 35 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 36 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 37 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 38 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 39 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | * 41 | ****************************************************************************** 42 | */ 43 | 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __fatfs_H 46 | #define __fatfs_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | #include "ff.h" 52 | #include "ff_gen_drv.h" 53 | #include "sd_diskio.h" /* defines SD_Driver as external */ 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern uint8_t retSD; /* Return value for SD */ 60 | extern char SD_Path[4]; /* SD logical drive path */ 61 | 62 | void MX_FATFS_Init(void); 63 | 64 | /* USER CODE BEGIN Prototypes */ 65 | 66 | /* USER CODE END Prototypes */ 67 | #ifdef __cplusplus 68 | } 69 | #endif 70 | #endif /*__fatfs_H */ 71 | 72 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 73 | -------------------------------------------------------------------------------- /Inc/gpio.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : gpio.h 4 | * Description : This file contains all the functions prototypes for 5 | * the gpio 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | /* Define to prevent recursive inclusion -------------------------------------*/ 46 | #ifndef __gpio_H 47 | #define __gpio_H 48 | #ifdef __cplusplus 49 | extern "C" { 50 | #endif 51 | 52 | /* Includes ------------------------------------------------------------------*/ 53 | #include "stm32f7xx_hal.h" 54 | #include "main.h" 55 | 56 | /* USER CODE BEGIN Includes */ 57 | 58 | /* USER CODE END Includes */ 59 | 60 | /* USER CODE BEGIN Private defines */ 61 | 62 | /* USER CODE END Private defines */ 63 | 64 | void MX_GPIO_Init(void); 65 | 66 | /* USER CODE BEGIN Prototypes */ 67 | 68 | /* USER CODE END Prototypes */ 69 | 70 | #ifdef __cplusplus 71 | } 72 | #endif 73 | #endif /*__ pinoutConfig_H */ 74 | 75 | /** 76 | * @} 77 | */ 78 | 79 | /** 80 | * @} 81 | */ 82 | 83 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 84 | -------------------------------------------------------------------------------- /Inc/i2c.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : I2C.h 4 | * Description : This file provides code for the configuration 5 | * of the I2C instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __i2c_H 46 | #define __i2c_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern I2C_HandleTypeDef hi2c2; 60 | extern I2C_HandleTypeDef hi2c4; 61 | 62 | /* USER CODE BEGIN Private defines */ 63 | 64 | /* USER CODE END Private defines */ 65 | 66 | extern void Error_Handler(void); 67 | 68 | void MX_I2C2_Init(void); 69 | void MX_I2C4_Init(void); 70 | 71 | /* USER CODE BEGIN Prototypes */ 72 | 73 | /* USER CODE END Prototypes */ 74 | 75 | #ifdef __cplusplus 76 | } 77 | #endif 78 | #endif /*__ i2c_H */ 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 89 | -------------------------------------------------------------------------------- /Inc/lwip.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : LWIP.h 4 | * Description : This file provides code for the configuration 5 | * of the LWIP. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ************************************************************************* 43 | 44 | */ 45 | /* Define to prevent recursive inclusion -------------------------------------*/ 46 | #ifndef __mx_lwip_H 47 | #define __mx_lwip_H 48 | #ifdef __cplusplus 49 | extern "C" { 50 | #endif 51 | 52 | /* Includes ------------------------------------------------------------------*/ 53 | #include "lwip/opt.h" 54 | #include "lwip/mem.h" 55 | #include "lwip/memp.h" 56 | #include "netif/etharp.h" 57 | #include "lwip/dhcp.h" 58 | #include "lwip/netif.h" 59 | #include "lwip/timeouts.h" 60 | #include "ethernetif.h" 61 | 62 | /* Includes for RTOS ---------------------------------------------------------*/ 63 | #if WITH_RTOS 64 | #include "lwip/tcpip.h" 65 | #endif /* WITH_RTOS */ 66 | 67 | /* USER CODE BEGIN 0 */ 68 | 69 | /* USER CODE END 0 */ 70 | 71 | /* Global Variables ----------------------------------------------------------*/ 72 | extern ETH_HandleTypeDef heth; 73 | 74 | /* LWIP init function */ 75 | void MX_LWIP_Init(void); 76 | 77 | /* USER CODE BEGIN 1 */ 78 | /* Function defined in lwip.c to: 79 | * - Read a received packet from the Ethernet buffers 80 | * - Send it to the lwIP stack for handling 81 | * - Handle timeouts if NO_SYS_NO_TIMERS not set 82 | */ 83 | void MX_LWIP_Process(void); 84 | 85 | /* USER CODE END 1 */ 86 | 87 | #ifdef __cplusplus 88 | } 89 | #endif 90 | #endif /*__ mx_lwip_H */ 91 | 92 | /** 93 | * @} 94 | */ 95 | 96 | /** 97 | * @} 98 | */ 99 | 100 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 101 | -------------------------------------------------------------------------------- /Inc/main.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : main.h 4 | * Description : This file contains the common defines of the application 5 | ****************************************************************************** 6 | * 7 | * Copyright (c) 2017 STMicroelectronics International N.V. 8 | * All rights reserved. 9 | * 10 | * Redistribution and use in source and binary forms, with or without 11 | * modification, are permitted, provided that the following conditions are met: 12 | * 13 | * 1. Redistribution of source code must retain the above copyright notice, 14 | * this list of conditions and the following disclaimer. 15 | * 2. Redistributions in binary form must reproduce the above copyright notice, 16 | * this list of conditions and the following disclaimer in the documentation 17 | * and/or other materials provided with the distribution. 18 | * 3. Neither the name of STMicroelectronics nor the names of other 19 | * contributors to this software may be used to endorse or promote products 20 | * derived from this software without specific written permission. 21 | * 4. This software, including modifications and/or derivative works of this 22 | * software, must execute solely and exclusively on microcontroller or 23 | * microprocessor devices manufactured by or for STMicroelectronics. 24 | * 5. Redistribution and use of this software other than as permitted under 25 | * this license is void and will automatically terminate your rights under 26 | * this license. 27 | * 28 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 29 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 30 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 31 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 32 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 33 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 35 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 36 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 37 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 38 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 39 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | * 41 | ****************************************************************************** 42 | */ 43 | /* Define to prevent recursive inclusion -------------------------------------*/ 44 | #ifndef __MAIN_H 45 | #define __MAIN_H 46 | /* Includes ------------------------------------------------------------------*/ 47 | 48 | /* USER CODE BEGIN Includes */ 49 | 50 | 51 | #include "stm32f7xx_ll_usart.h" 52 | #include "stm32f7xx_ll_dma.h" 53 | 54 | 55 | 56 | // #include "stm32f7xx_ll_gpio.h" 57 | // #include "stm32f7xx_ll_bus.h" 58 | // #include "stm32f7xx_ll_rcc.h" 59 | /* USER CODE END Includes */ 60 | 61 | /* Private define ------------------------------------------------------------*/ 62 | 63 | 64 | /* USER CODE BEGIN Private defines */ 65 | 66 | /* USER CODE END Private defines */ 67 | 68 | /** 69 | * @} 70 | */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | #endif /* __MAIN_H */ 77 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 78 | -------------------------------------------------------------------------------- /Inc/quadspi.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : QUADSPI.h 4 | * Description : This file provides code for the configuration 5 | * of the QUADSPI instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __quadspi_H 46 | #define __quadspi_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern QSPI_HandleTypeDef hqspi; 60 | 61 | /* USER CODE BEGIN Private defines */ 62 | 63 | /* USER CODE END Private defines */ 64 | 65 | extern void Error_Handler(void); 66 | 67 | void MX_QUADSPI_Init(void); 68 | 69 | /* USER CODE BEGIN Prototypes */ 70 | 71 | /* USER CODE END Prototypes */ 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | #endif /*__ quadspi_H */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 87 | -------------------------------------------------------------------------------- /Inc/sai.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : SAI.h 4 | * Description : This file provides code for the configuration 5 | * of the SAI instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __sai_H 46 | #define __sai_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern SAI_HandleTypeDef hsai_BlockA1; 60 | 61 | /* USER CODE BEGIN Private defines */ 62 | 63 | /* USER CODE END Private defines */ 64 | 65 | extern void Error_Handler(void); 66 | 67 | void MX_SAI1_Init(void); 68 | 69 | /* USER CODE BEGIN Prototypes */ 70 | 71 | /* USER CODE END Prototypes */ 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | #endif /*__ sai_H */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 87 | -------------------------------------------------------------------------------- /Inc/sdmmc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : SDMMC.h 4 | * Description : This file provides code for the configuration 5 | * of the SDMMC instances. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __sdmmc_H 46 | #define __sdmmc_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx_hal.h" 53 | #include "main.h" 54 | 55 | /* USER CODE BEGIN Includes */ 56 | 57 | /* USER CODE END Includes */ 58 | 59 | extern SD_HandleTypeDef hsd1; 60 | extern SD_HandleTypeDef hsd2; 61 | 62 | /* USER CODE BEGIN Private defines */ 63 | 64 | /* USER CODE END Private defines */ 65 | 66 | extern void Error_Handler(void); 67 | 68 | void MX_SDMMC1_SD_Init(void); 69 | void MX_SDMMC2_SD_Init(void); 70 | 71 | /* USER CODE BEGIN Prototypes */ 72 | 73 | /* USER CODE END Prototypes */ 74 | 75 | #ifdef __cplusplus 76 | } 77 | #endif 78 | #endif /*__ sdmmc_H */ 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 89 | -------------------------------------------------------------------------------- /Inc/stm32f7xx_it.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f7xx_it.h 4 | * @brief This file contains the headers of the interrupt handlers. 5 | ****************************************************************************** 6 | * 7 | * COPYRIGHT(c) 2017 STMicroelectronics 8 | * 9 | * Redistribution and use in source and binary forms, with or without modification, 10 | * are permitted provided that the following conditions are met: 11 | * 1. Redistributions of source code must retain the above copyright notice, 12 | * this list of conditions and the following disclaimer. 13 | * 2. Redistributions in binary form must reproduce the above copyright notice, 14 | * this list of conditions and the following disclaimer in the documentation 15 | * and/or other materials provided with the distribution. 16 | * 3. Neither the name of STMicroelectronics nor the names of its contributors 17 | * may be used to endorse or promote products derived from this software 18 | * without specific prior written permission. 19 | * 20 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | * 31 | ****************************************************************************** 32 | */ 33 | 34 | /* Define to prevent recursive inclusion -------------------------------------*/ 35 | #ifndef __STM32F7xx_IT_H 36 | #define __STM32F7xx_IT_H 37 | 38 | #ifdef __cplusplus 39 | extern "C" { 40 | #endif 41 | 42 | /* Includes ------------------------------------------------------------------*/ 43 | /* Exported types ------------------------------------------------------------*/ 44 | /* Exported constants --------------------------------------------------------*/ 45 | /* Exported macro ------------------------------------------------------------*/ 46 | /* Exported functions ------------------------------------------------------- */ 47 | 48 | void SysTick_Handler(void); 49 | void TIM6_DAC_IRQHandler(void); 50 | void ETH_IRQHandler(void); 51 | void OTG_FS_IRQHandler(void); 52 | 53 | #ifdef __cplusplus 54 | } 55 | #endif 56 | 57 | #endif /* __STM32F7xx_IT_H */ 58 | 59 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 60 | -------------------------------------------------------------------------------- /Inc/usb_device.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : USB_DEVICE 4 | * @version : v1.0_Cube 5 | * @brief : Header for usb_device file. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __usb_device_H 46 | #define __usb_device_H 47 | #ifdef __cplusplus 48 | extern "C" { 49 | #endif 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "stm32f7xx.h" 53 | #include "stm32f7xx_hal.h" 54 | #include "usbd_def.h" 55 | 56 | extern USBD_HandleTypeDef hUsbDeviceFS; 57 | 58 | /* USB_Device init function */ 59 | void MX_USB_DEVICE_Init(void); 60 | 61 | #ifdef __cplusplus 62 | } 63 | #endif 64 | #endif /*__usb_device_H */ 65 | 66 | /** 67 | * @} 68 | */ 69 | 70 | /** 71 | * @} 72 | */ 73 | 74 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 75 | -------------------------------------------------------------------------------- /Inc/usbd_cdc_if.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : usbd_cdc_if.h 4 | * @brief : Header for usbd_cdc_if file. 5 | ****************************************************************************** 6 | * 7 | * Copyright (c) 2017 STMicroelectronics International N.V. 8 | * All rights reserved. 9 | * 10 | * Redistribution and use in source and binary forms, with or without 11 | * modification, are permitted, provided that the following conditions are met: 12 | * 13 | * 1. Redistribution of source code must retain the above copyright notice, 14 | * this list of conditions and the following disclaimer. 15 | * 2. Redistributions in binary form must reproduce the above copyright notice, 16 | * this list of conditions and the following disclaimer in the documentation 17 | * and/or other materials provided with the distribution. 18 | * 3. Neither the name of STMicroelectronics nor the names of other 19 | * contributors to this software may be used to endorse or promote products 20 | * derived from this software without specific written permission. 21 | * 4. This software, including modifications and/or derivative works of this 22 | * software, must execute solely and exclusively on microcontroller or 23 | * microprocessor devices manufactured by or for STMicroelectronics. 24 | * 5. Redistribution and use of this software other than as permitted under 25 | * this license is void and will automatically terminate your rights under 26 | * this license. 27 | * 28 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 29 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 30 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 31 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 32 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 33 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 35 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 36 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 37 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 38 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 39 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | * 41 | ****************************************************************************** 42 | */ 43 | 44 | /* Define to prevent recursive inclusion -------------------------------------*/ 45 | #ifndef __USBD_CDC_IF_H 46 | #define __USBD_CDC_IF_H 47 | 48 | #ifdef __cplusplus 49 | extern "C" { 50 | #endif 51 | /* Includes ------------------------------------------------------------------*/ 52 | #include "usbd_cdc.h" 53 | /* USER CODE BEGIN INCLUDE */ 54 | /* USER CODE END INCLUDE */ 55 | 56 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 57 | * @{ 58 | */ 59 | 60 | /** @defgroup USBD_CDC_IF 61 | * @brief header 62 | * @{ 63 | */ 64 | 65 | /** @defgroup USBD_CDC_IF_Exported_Defines 66 | * @{ 67 | */ 68 | /* USER CODE BEGIN EXPORTED_DEFINES */ 69 | /* USER CODE END EXPORTED_DEFINES */ 70 | 71 | /** 72 | * @} 73 | */ 74 | 75 | /** @defgroup USBD_CDC_IF_Exported_Types 76 | * @{ 77 | */ 78 | /* USER CODE BEGIN EXPORTED_TYPES */ 79 | /* USER CODE END EXPORTED_TYPES */ 80 | 81 | /** 82 | * @} 83 | */ 84 | 85 | /** @defgroup USBD_CDC_IF_Exported_Macros 86 | * @{ 87 | */ 88 | /* USER CODE BEGIN EXPORTED_MACRO */ 89 | /* USER CODE END EXPORTED_MACRO */ 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | /** @defgroup USBD_AUDIO_IF_Exported_Variables 96 | * @{ 97 | */ 98 | extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS; 99 | 100 | /* USER CODE BEGIN EXPORTED_VARIABLES */ 101 | /* USER CODE END EXPORTED_VARIABLES */ 102 | 103 | /** 104 | * @} 105 | */ 106 | 107 | /** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype 108 | * @{ 109 | */ 110 | uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len); 111 | 112 | /* USER CODE BEGIN EXPORTED_FUNCTIONS */ 113 | /* USER CODE END EXPORTED_FUNCTIONS */ 114 | /** 115 | * @} 116 | */ 117 | 118 | /** 119 | * @} 120 | */ 121 | 122 | /** 123 | * @} 124 | */ 125 | 126 | #ifdef __cplusplus 127 | } 128 | #endif 129 | 130 | #endif /* __USBD_CDC_IF_H */ 131 | 132 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 133 | -------------------------------------------------------------------------------- /Inc/usbd_desc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : usbd_desc.h 4 | * @version : v1.0_Cube 5 | * @brief : Header for usbd_desc file. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | /* Define to prevent recursive inclusion -------------------------------------*/ 46 | #ifndef __USBD_DESC__H__ 47 | #define __USBD_DESC__H__ 48 | 49 | #ifdef __cplusplus 50 | extern "C" { 51 | #endif 52 | /* Includes ------------------------------------------------------------------*/ 53 | #include "usbd_def.h" 54 | 55 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 56 | * @{ 57 | */ 58 | 59 | /** @defgroup USB_DESC 60 | * @brief general defines for the usb device library file 61 | * @{ 62 | */ 63 | 64 | /** @defgroup USB_DESC_Exported_Defines 65 | * @{ 66 | */ 67 | 68 | /** 69 | * @} 70 | */ 71 | 72 | /** @defgroup USBD_DESC_Exported_TypesDefinitions 73 | * @{ 74 | */ 75 | /** 76 | * @} 77 | */ 78 | 79 | /** @defgroup USBD_DESC_Exported_Macros 80 | * @{ 81 | */ 82 | /** 83 | * @} 84 | */ 85 | 86 | /** @defgroup USBD_DESC_Exported_Variables 87 | * @{ 88 | */ 89 | extern USBD_DescriptorsTypeDef FS_Desc; 90 | /** 91 | * @} 92 | */ 93 | 94 | /** @defgroup USBD_DESC_Exported_FunctionsPrototype 95 | * @{ 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | #ifdef __cplusplus 102 | } 103 | #endif 104 | 105 | #endif /* __USBD_DESC_H */ 106 | 107 | /** 108 | * @} 109 | */ 110 | 111 | /** 112 | * @} 113 | */ 114 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 115 | -------------------------------------------------------------------------------- /LICENSE.md: -------------------------------------------------------------------------------- 1 | The EEDrone firmware is licensed generally under a permissive 3-clause BSD license. Contributions are required 2 | to be made under the same license. Any exception to this general rule is listed below. 3 | 4 | /**************************************************************************** 5 | * 6 | * Copyright (c) 2016-2017 EEDrone Development Team. All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * 1. Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * 2. Redistributions in binary form must reproduce the above copyright 15 | * notice, this list of conditions and the following disclaimer in 16 | * the documentation and/or other materials provided with the 17 | * distribution. 18 | * 3. Neither the name EEDrone nor the names of its contributors may be 19 | * used to endorse or promote products derived from this software 20 | * without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS 29 | * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED 30 | * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | * 35 | ****************************************************************************/ 36 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_req.h 4 | * @author MCD Application Team 5 | * @version V2.4.2 6 | * @date 11-December-2015 7 | * @brief Header file for the usbd_req.c file 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT 2015 STMicroelectronics

12 | * 13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); 14 | * You may not use this file except in compliance with the License. 15 | * You may obtain a copy of the License at: 16 | * 17 | * http://www.st.com/software_license_agreement_liberty_v2 18 | * 19 | * Unless required by applicable law or agreed to in writing, software 20 | * distributed under the License is distributed on an "AS IS" BASIS, 21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 22 | * See the License for the specific language governing permissions and 23 | * limitations under the License. 24 | * 25 | ****************************************************************************** 26 | */ 27 | 28 | /* Define to prevent recursive inclusion -------------------------------------*/ 29 | #ifndef __USB_REQUEST_H 30 | #define __USB_REQUEST_H 31 | 32 | #ifdef __cplusplus 33 | extern "C" { 34 | #endif 35 | 36 | /* Includes ------------------------------------------------------------------*/ 37 | #include "usbd_def.h" 38 | 39 | 40 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 41 | * @{ 42 | */ 43 | 44 | /** @defgroup USBD_REQ 45 | * @brief header file for the usbd_req.c file 46 | * @{ 47 | */ 48 | 49 | /** @defgroup USBD_REQ_Exported_Defines 50 | * @{ 51 | */ 52 | /** 53 | * @} 54 | */ 55 | 56 | 57 | /** @defgroup USBD_REQ_Exported_Types 58 | * @{ 59 | */ 60 | /** 61 | * @} 62 | */ 63 | 64 | 65 | 66 | /** @defgroup USBD_REQ_Exported_Macros 67 | * @{ 68 | */ 69 | /** 70 | * @} 71 | */ 72 | 73 | /** @defgroup USBD_REQ_Exported_Variables 74 | * @{ 75 | */ 76 | /** 77 | * @} 78 | */ 79 | 80 | /** @defgroup USBD_REQ_Exported_FunctionsPrototype 81 | * @{ 82 | */ 83 | 84 | USBD_StatusTypeDef USBD_StdDevReq (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 85 | USBD_StatusTypeDef USBD_StdItfReq (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 86 | USBD_StatusTypeDef USBD_StdEPReq (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 87 | 88 | 89 | void USBD_CtlError (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 90 | 91 | void USBD_ParseSetupRequest (USBD_SetupReqTypedef *req, uint8_t *pdata); 92 | 93 | void USBD_GetString (uint8_t *desc, uint8_t *unicode, uint16_t *len); 94 | /** 95 | * @} 96 | */ 97 | 98 | #ifdef __cplusplus 99 | } 100 | #endif 101 | 102 | #endif /* __USB_REQUEST_H */ 103 | 104 | /** 105 | * @} 106 | */ 107 | 108 | /** 109 | * @} 110 | */ 111 | 112 | 113 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 114 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_ioreq.h 4 | * @author MCD Application Team 5 | * @version V2.4.2 6 | * @date 11-December-2015 7 | * @brief Header file for the usbd_ioreq.c file 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT 2015 STMicroelectronics

12 | * 13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); 14 | * You may not use this file except in compliance with the License. 15 | * You may obtain a copy of the License at: 16 | * 17 | * http://www.st.com/software_license_agreement_liberty_v2 18 | * 19 | * Unless required by applicable law or agreed to in writing, software 20 | * distributed under the License is distributed on an "AS IS" BASIS, 21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 22 | * See the License for the specific language governing permissions and 23 | * limitations under the License. 24 | * 25 | ****************************************************************************** 26 | */ 27 | 28 | /* Define to prevent recursive inclusion -------------------------------------*/ 29 | #ifndef __USBD_IOREQ_H 30 | #define __USBD_IOREQ_H 31 | 32 | #ifdef __cplusplus 33 | extern "C" { 34 | #endif 35 | 36 | /* Includes ------------------------------------------------------------------*/ 37 | #include "usbd_def.h" 38 | #include "usbd_core.h" 39 | 40 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 41 | * @{ 42 | */ 43 | 44 | /** @defgroup USBD_IOREQ 45 | * @brief header file for the usbd_ioreq.c file 46 | * @{ 47 | */ 48 | 49 | /** @defgroup USBD_IOREQ_Exported_Defines 50 | * @{ 51 | */ 52 | /** 53 | * @} 54 | */ 55 | 56 | 57 | /** @defgroup USBD_IOREQ_Exported_Types 58 | * @{ 59 | */ 60 | 61 | 62 | /** 63 | * @} 64 | */ 65 | 66 | 67 | 68 | /** @defgroup USBD_IOREQ_Exported_Macros 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_IOREQ_Exported_Variables 77 | * @{ 78 | */ 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | /** @defgroup USBD_IOREQ_Exported_FunctionsPrototype 85 | * @{ 86 | */ 87 | 88 | USBD_StatusTypeDef USBD_CtlSendData (USBD_HandleTypeDef *pdev, 89 | uint8_t *buf, 90 | uint16_t len); 91 | 92 | USBD_StatusTypeDef USBD_CtlContinueSendData (USBD_HandleTypeDef *pdev, 93 | uint8_t *pbuf, 94 | uint16_t len); 95 | 96 | USBD_StatusTypeDef USBD_CtlPrepareRx (USBD_HandleTypeDef *pdev, 97 | uint8_t *pbuf, 98 | uint16_t len); 99 | 100 | USBD_StatusTypeDef USBD_CtlContinueRx (USBD_HandleTypeDef *pdev, 101 | uint8_t *pbuf, 102 | uint16_t len); 103 | 104 | USBD_StatusTypeDef USBD_CtlSendStatus (USBD_HandleTypeDef *pdev); 105 | 106 | USBD_StatusTypeDef USBD_CtlReceiveStatus (USBD_HandleTypeDef *pdev); 107 | 108 | uint16_t USBD_GetRxCount (USBD_HandleTypeDef *pdev , 109 | uint8_t epnum); 110 | 111 | /** 112 | * @} 113 | */ 114 | 115 | #ifdef __cplusplus 116 | } 117 | #endif 118 | 119 | #endif /* __USBD_IOREQ_H */ 120 | 121 | /** 122 | * @} 123 | */ 124 | 125 | /** 126 | * @} 127 | */ 128 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 129 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FatFs/src/diskio.h: -------------------------------------------------------------------------------- 1 | /*-----------------------------------------------------------------------/ 2 | / Low level disk interface modlue include file (C)ChaN, 2014 / 3 | /-----------------------------------------------------------------------*/ 4 | 5 | #ifndef _DISKIO_DEFINED 6 | #define _DISKIO_DEFINED 7 | 8 | #ifdef __cplusplus 9 | extern "C" { 10 | #endif 11 | 12 | #define _USE_WRITE 1 /* 1: Enable disk_write function */ 13 | #define _USE_IOCTL 1 /* 1: Enable disk_ioctl fucntion */ 14 | 15 | #include "integer.h" 16 | 17 | 18 | /* Status of Disk Functions */ 19 | typedef BYTE DSTATUS; 20 | 21 | /* Results of Disk Functions */ 22 | typedef enum { 23 | RES_OK = 0, /* 0: Successful */ 24 | RES_ERROR, /* 1: R/W Error */ 25 | RES_WRPRT, /* 2: Write Protected */ 26 | RES_NOTRDY, /* 3: Not Ready */ 27 | RES_PARERR /* 4: Invalid Parameter */ 28 | } DRESULT; 29 | 30 | 31 | /*---------------------------------------*/ 32 | /* Prototypes for disk control functions */ 33 | 34 | 35 | DSTATUS disk_initialize (BYTE pdrv); 36 | DSTATUS disk_status (BYTE pdrv); 37 | DRESULT disk_read (BYTE pdrv, BYTE* buff, DWORD sector, UINT count); 38 | DRESULT disk_write (BYTE pdrv, const BYTE* buff, DWORD sector, UINT count); 39 | DRESULT disk_ioctl (BYTE pdrv, BYTE cmd, void* buff); 40 | DWORD get_fattime (void); 41 | 42 | /* Disk Status Bits (DSTATUS) */ 43 | 44 | #define STA_NOINIT 0x01 /* Drive not initialized */ 45 | #define STA_NODISK 0x02 /* No medium in the drive */ 46 | #define STA_PROTECT 0x04 /* Write protected */ 47 | 48 | 49 | /* Command code for disk_ioctrl fucntion */ 50 | 51 | /* Generic command (Used by FatFs) */ 52 | #define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */ 53 | #define GET_SECTOR_COUNT 1 /* Get media size (needed at _USE_MKFS == 1) */ 54 | #define GET_SECTOR_SIZE 2 /* Get sector size (needed at _MAX_SS != _MIN_SS) */ 55 | #define GET_BLOCK_SIZE 3 /* Get erase block size (needed at _USE_MKFS == 1) */ 56 | #define CTRL_TRIM 4 /* Inform device that the data on the block of sectors is no longer used (needed at _USE_TRIM == 1) */ 57 | 58 | /* Generic command (Not used by FatFs) */ 59 | #define CTRL_POWER 5 /* Get/Set power status */ 60 | #define CTRL_LOCK 6 /* Lock/Unlock media removal */ 61 | #define CTRL_EJECT 7 /* Eject media */ 62 | #define CTRL_FORMAT 8 /* Create physical format on the media */ 63 | 64 | /* MMC/SDC specific ioctl command */ 65 | #define MMC_GET_TYPE 10 /* Get card type */ 66 | #define MMC_GET_CSD 11 /* Get CSD */ 67 | #define MMC_GET_CID 12 /* Get CID */ 68 | #define MMC_GET_OCR 13 /* Get OCR */ 69 | #define MMC_GET_SDSTAT 14 /* Get SD status */ 70 | 71 | /* ATA/CF specific ioctl command */ 72 | #define ATA_GET_REV 20 /* Get F/W revision */ 73 | #define ATA_GET_MODEL 21 /* Get model name */ 74 | #define ATA_GET_SN 22 /* Get serial number */ 75 | 76 | #ifdef __cplusplus 77 | } 78 | #endif 79 | 80 | #endif 81 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FatFs/src/drivers/sd_diskio.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file sd_diskio.h 4 | * @author MCD Application Team 5 | * @version V1.4.0 6 | * @date 23-December-2016 7 | * @brief Header for sd_diskio.c module 8 | ****************************************************************************** 9 | * @attention 10 | * 11 | *

© COPYRIGHT 2016 STMicroelectronics

12 | * 13 | * Redistribution and use in source and binary forms, with or without 14 | * modification, are permitted, provided that the following conditions are met: 15 | * 16 | * 1. Redistribution of source code must retain the above copyright notice, 17 | * this list of conditions and the following disclaimer. 18 | * 2. Redistributions in binary form must reproduce the above copyright notice, 19 | * this list of conditions and the following disclaimer in the documentation 20 | * and/or other materials provided with the distribution. 21 | * 3. Neither the name of STMicroelectronics nor the names of other 22 | * contributors to this software may be used to endorse or promote products 23 | * derived from this software without specific written permission. 24 | * 4. This software, including modifications and/or derivative works of this 25 | * software, must execute solely and exclusively on microcontroller or 26 | * microprocessor devices manufactured by or for STMicroelectronics. 27 | * 5. Redistribution and use of this software other than as permitted under 28 | * this license is void and will automatically terminate your rights under 29 | * this license. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 33 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 34 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 35 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 36 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 37 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 38 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 39 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 40 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 41 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 42 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 43 | * 44 | ****************************************************************************** 45 | */ 46 | 47 | /* Define to prevent recursive inclusion -------------------------------------*/ 48 | #ifndef __SD_DISKIO_H 49 | #define __SD_DISKIO_H 50 | 51 | /* Includes ------------------------------------------------------------------*/ 52 | /* Exported types ------------------------------------------------------------*/ 53 | /* Exported constants --------------------------------------------------------*/ 54 | /* Exported functions ------------------------------------------------------- */ 55 | extern Diskio_drvTypeDef SD_Driver; 56 | 57 | #endif /* __SD_DISKIO_H */ 58 | 59 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 60 | 61 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FatFs/src/integer.h: -------------------------------------------------------------------------------- 1 | /*-------------------------------------------*/ 2 | /* Integer type definitions for FatFs module */ 3 | /*-------------------------------------------*/ 4 | 5 | #ifndef _FF_INTEGER 6 | #define _FF_INTEGER 7 | 8 | #ifdef _WIN32 /* FatFs development platform */ 9 | 10 | #include 11 | #include 12 | 13 | #else /* Embedded platform */ 14 | 15 | /* This type MUST be 8 bit */ 16 | typedef unsigned char BYTE; 17 | 18 | /* These types MUST be 16 bit */ 19 | typedef short SHORT; 20 | typedef unsigned short WORD; 21 | typedef unsigned short WCHAR; 22 | 23 | /* These types MUST be 16 bit or 32 bit */ 24 | typedef int INT; 25 | typedef unsigned int UINT; 26 | 27 | /* These types MUST be 32 bit */ 28 | typedef long LONG; 29 | typedef unsigned long DWORD; 30 | 31 | #endif 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FatFs/src/option/syscall.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------*/ 2 | /* Sample code of OS dependent controls for FatFs */ 3 | /* (C)ChaN, 2014 */ 4 | /*------------------------------------------------------------------------*/ 5 | 6 | #include /* ANSI memory controls */ 7 | #include "../ff.h" 8 | 9 | #if _FS_REENTRANT 10 | /*----------------------------------------------------------------------- 11 | Create a Synchronization Object 12 | ------------------------------------------------------------------------ 13 | This function is called in f_mount function to create a new 14 | synchronization object, such as semaphore and mutex. When a zero is 15 | returned, the f_mount function fails with FR_INT_ERR. 16 | */ 17 | 18 | int ff_cre_syncobj ( /* TRUE:Function succeeded, FALSE:Could not create due to any error */ 19 | BYTE vol, /* Corresponding logical drive being processed */ 20 | _SYNC_t *sobj /* Pointer to return the created sync object */ 21 | ) 22 | { 23 | int ret; 24 | 25 | osSemaphoreDef(SEM); 26 | *sobj = osSemaphoreCreate(osSemaphore(SEM), 1); 27 | ret = (*sobj != NULL); 28 | 29 | return ret; 30 | } 31 | 32 | 33 | 34 | /*------------------------------------------------------------------------*/ 35 | /* Delete a Synchronization Object */ 36 | /*------------------------------------------------------------------------*/ 37 | /* This function is called in f_mount function to delete a synchronization 38 | / object that created with ff_cre_syncobj function. When a zero is 39 | / returned, the f_mount function fails with FR_INT_ERR. 40 | */ 41 | 42 | int ff_del_syncobj ( /* TRUE:Function succeeded, FALSE:Could not delete due to any error */ 43 | _SYNC_t sobj /* Sync object tied to the logical drive to be deleted */ 44 | ) 45 | { 46 | osSemaphoreDelete (sobj); 47 | return 1; 48 | } 49 | 50 | 51 | 52 | /*------------------------------------------------------------------------*/ 53 | /* Request Grant to Access the Volume */ 54 | /*------------------------------------------------------------------------*/ 55 | /* This function is called on entering file functions to lock the volume. 56 | / When a zero is returned, the file function fails with FR_TIMEOUT. 57 | */ 58 | 59 | int ff_req_grant ( /* TRUE:Got a grant to access the volume, FALSE:Could not get a grant */ 60 | _SYNC_t sobj /* Sync object to wait */ 61 | ) 62 | { 63 | int ret = 0; 64 | 65 | if(osSemaphoreWait(sobj, _FS_TIMEOUT) == osOK) 66 | { 67 | ret = 1; 68 | } 69 | 70 | return ret; 71 | } 72 | 73 | 74 | 75 | /*------------------------------------------------------------------------*/ 76 | /* Release Grant to Access the Volume */ 77 | /*------------------------------------------------------------------------*/ 78 | /* This function is called on leaving file functions to unlock the volume. 79 | */ 80 | 81 | void ff_rel_grant ( 82 | _SYNC_t sobj /* Sync object to be signaled */ 83 | ) 84 | { 85 | osSemaphoreRelease(sobj); 86 | } 87 | 88 | #endif 89 | 90 | 91 | 92 | 93 | #if _USE_LFN == 3 /* LFN with a working buffer on the heap */ 94 | /*------------------------------------------------------------------------*/ 95 | /* Allocate a memory block */ 96 | /*------------------------------------------------------------------------*/ 97 | /* If a NULL is returned, the file function fails with FR_NOT_ENOUGH_CORE. 98 | */ 99 | 100 | void* ff_memalloc ( /* Returns pointer to the allocated memory block */ 101 | UINT msize /* Number of bytes to allocate */ 102 | ) 103 | { 104 | return malloc(msize); /* Allocate a new memory block with POSIX API */ 105 | } 106 | 107 | 108 | /*------------------------------------------------------------------------*/ 109 | /* Free a memory block */ 110 | /*------------------------------------------------------------------------*/ 111 | 112 | void ff_memfree ( 113 | void* mblock /* Pointer to the memory block to free */ 114 | ) 115 | { 116 | free(mblock); /* Discard the memory block with POSIX API */ 117 | } 118 | 119 | #endif 120 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS-Plus-CLI/UARTCommandConsole.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Middlewares/Third_Party/FreeRTOS-Plus-CLI/UARTCommandConsole.c -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.c -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/UARTCommandConsole.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/EEDrone/Firmware/98d3d5969d87e3986ba10375fed9ac72fd81d35a/Middlewares/Third_Party/FreeRTOS/Source/UARTCommandConsole.c -------------------------------------------------------------------------------- /Modules/AHRS/CKF.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _CKF_H 25 | #define _CKF_H 26 | 27 | #include "Matrix.h" 28 | 29 | //7-state q0 q1 q2 q3 wx wy wz 30 | #define CKF_STATE_DIM 7 31 | //13-measurement q0 q1 q2 q3 ax ay az wx wy wz mx my mz 32 | #define CKF_MEASUREMENT_DIM 13 33 | 34 | #define CKF_CP_POINTS 14//(2 * CKF_STATE_DIM) 35 | 36 | #define CKF_HALFPI 1.5707963267948966192313216916398f 37 | #define CKF_PI 3.1415926535897932384626433832795f 38 | #define CKF_TWOPI 6.283185307179586476925286766559f 39 | #define CKF_TODEG(x) ((x) * 57.2957796f) 40 | 41 | typedef struct CKF_FILTER_T{ 42 | //weights 43 | float32_t W; 44 | //Kesi 45 | float32_t Kesi_f32[CKF_STATE_DIM * CKF_CP_POINTS]; 46 | float32_t iKesi_f32[CKF_STATE_DIM]; 47 | //state covariance 48 | float32_t P_f32[CKF_STATE_DIM * CKF_STATE_DIM]; 49 | float32_t PX_f32[CKF_STATE_DIM * CKF_STATE_DIM]; 50 | float32_t PY_f32[CKF_MEASUREMENT_DIM * CKF_MEASUREMENT_DIM]; 51 | float32_t tmpPY_f32[CKF_MEASUREMENT_DIM * CKF_MEASUREMENT_DIM]; 52 | float32_t PXY_f32[CKF_STATE_DIM * CKF_MEASUREMENT_DIM]; 53 | float32_t tmpPXY_f32[CKF_STATE_DIM * CKF_MEASUREMENT_DIM]; 54 | float32_t Q_f32[CKF_STATE_DIM * CKF_STATE_DIM]; 55 | float32_t R_f32[CKF_MEASUREMENT_DIM * CKF_MEASUREMENT_DIM]; 56 | //cubature points 57 | float32_t XCP_f32[CKF_STATE_DIM * CKF_CP_POINTS]; 58 | float32_t XminusCP_f32[CKF_STATE_DIM * CKF_CP_POINTS]; 59 | float32_t YSP_f32[CKF_MEASUREMENT_DIM * CKF_CP_POINTS]; 60 | 61 | //Kalman gain 62 | float32_t K_f32[CKF_STATE_DIM * CKF_MEASUREMENT_DIM]; 63 | float32_t KT_f32[CKF_MEASUREMENT_DIM * CKF_STATE_DIM]; 64 | //state vector 65 | float32_t X_f32[CKF_STATE_DIM]; 66 | float32_t XT_f32[CKF_STATE_DIM]; 67 | float32_t Xminus_f32[CKF_STATE_DIM]; 68 | float32_t XminusT_f32[CKF_STATE_DIM]; 69 | float32_t tmpX_f32[CKF_STATE_DIM]; 70 | float32_t tmpS_f32[CKF_STATE_DIM]; 71 | //measurement vector 72 | float32_t Y_f32[CKF_MEASUREMENT_DIM]; 73 | float32_t YT_f32[CKF_MEASUREMENT_DIM]; 74 | float32_t Yminus_f32[CKF_MEASUREMENT_DIM]; 75 | float32_t YminusT_f32[CKF_MEASUREMENT_DIM]; 76 | float32_t tmpY_f32[CKF_MEASUREMENT_DIM]; 77 | // 78 | arm_matrix_instance_f32 Kesi; 79 | arm_matrix_instance_f32 iKesi; 80 | arm_matrix_instance_f32 P; 81 | arm_matrix_instance_f32 PX; 82 | arm_matrix_instance_f32 PY; 83 | arm_matrix_instance_f32 tmpPY; 84 | arm_matrix_instance_f32 PXY; 85 | arm_matrix_instance_f32 tmpPXY; 86 | arm_matrix_instance_f32 Q; 87 | arm_matrix_instance_f32 R; 88 | // 89 | arm_matrix_instance_f32 XCP; 90 | arm_matrix_instance_f32 XminusCP; 91 | arm_matrix_instance_f32 YCP; 92 | // 93 | arm_matrix_instance_f32 K; 94 | arm_matrix_instance_f32 KT; 95 | // 96 | arm_matrix_instance_f32 X; 97 | arm_matrix_instance_f32 XT; 98 | arm_matrix_instance_f32 Xminus; 99 | arm_matrix_instance_f32 XminusT; 100 | arm_matrix_instance_f32 tmpX; 101 | arm_matrix_instance_f32 tmpS; 102 | arm_matrix_instance_f32 Y; 103 | arm_matrix_instance_f32 YT; 104 | arm_matrix_instance_f32 Yminus; 105 | arm_matrix_instance_f32 YminusT; 106 | arm_matrix_instance_f32 tmpY; 107 | }CKF_Filter; 108 | 109 | void CKF_New(CKF_Filter* ckf); 110 | void CKF_Init(CKF_Filter* ckf, float32_t *q, float32_t *gyro); 111 | void CKF_Update(CKF_Filter* ckf, float32_t *q, float32_t *gyro, float32_t *accel, float32_t *mag, float32_t dt); 112 | void CKF_GetAngle(CKF_Filter* ckf, float32_t* rpy); 113 | 114 | inline void CKF_GetQ(CKF_Filter* ckf, float32_t* Q) 115 | { 116 | Q[0] = ckf->X_f32[0]; 117 | Q[1] = ckf->X_f32[1]; 118 | Q[2] = ckf->X_f32[2]; 119 | Q[3] = ckf->X_f32[3]; 120 | } 121 | 122 | #endif 123 | -------------------------------------------------------------------------------- /Modules/AHRS/EKF.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _EKF_H 25 | #define _EKF_H 26 | 27 | #include "Matrix.h" 28 | 29 | //7-state q0 q1 q2 q3 wx wy wz 30 | #define EKF_STATE_DIM 7 31 | //13-measurement q0 q1 q2 q3 ax ay az wx wy wz mx my mz 32 | #define EKF_MEASUREMENT_DIM 13 33 | 34 | #define EKF_HALFPI 1.5707963267948966192313216916398f 35 | #define EKF_PI 3.1415926535897932384626433832795f 36 | #define EKF_TWOPI 6.283185307179586476925286766559f 37 | #define EKF_TODEG(x) ((x) * 57.2957796f) 38 | 39 | typedef struct EKF_FILTER_T{ 40 | //state covariance 41 | float32_t P_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 42 | float32_t Q_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 43 | float32_t R_f32[EKF_MEASUREMENT_DIM * EKF_MEASUREMENT_DIM]; 44 | //Kalman gain 45 | float32_t K_f32[EKF_STATE_DIM * EKF_MEASUREMENT_DIM]; 46 | float32_t KT_f32[EKF_MEASUREMENT_DIM * EKF_STATE_DIM]; 47 | //Measurement covariance 48 | float32_t S_f32[EKF_MEASUREMENT_DIM * EKF_MEASUREMENT_DIM]; 49 | //The H matrix maps the measurement to the states 50 | float32_t F_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 51 | float32_t FT_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 52 | float32_t H_f32[EKF_MEASUREMENT_DIM * EKF_STATE_DIM]; 53 | float32_t HT_f32[EKF_STATE_DIM * EKF_MEASUREMENT_DIM]; 54 | float32_t I_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 55 | //state vector 56 | float32_t X_f32[EKF_STATE_DIM]; 57 | //measurement vector 58 | float32_t Y_f32[EKF_MEASUREMENT_DIM]; 59 | // 60 | float32_t tmpP_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 61 | float32_t tmpS_f32[EKF_MEASUREMENT_DIM * EKF_MEASUREMENT_DIM]; 62 | float32_t tmpX_f32[EKF_STATE_DIM]; 63 | float32_t tmpXX_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 64 | float32_t tmpXXT_f32[EKF_STATE_DIM * EKF_STATE_DIM]; 65 | float32_t tmpXY_f32[EKF_STATE_DIM * EKF_MEASUREMENT_DIM]; 66 | float32_t tmpYX_f32[EKF_MEASUREMENT_DIM * EKF_STATE_DIM]; 67 | 68 | arm_matrix_instance_f32 P; 69 | arm_matrix_instance_f32 Q; 70 | arm_matrix_instance_f32 R; 71 | arm_matrix_instance_f32 K; 72 | arm_matrix_instance_f32 KT; 73 | arm_matrix_instance_f32 S; 74 | arm_matrix_instance_f32 F; 75 | arm_matrix_instance_f32 FT; 76 | arm_matrix_instance_f32 H; 77 | arm_matrix_instance_f32 HT; 78 | arm_matrix_instance_f32 I; 79 | // 80 | arm_matrix_instance_f32 X; 81 | arm_matrix_instance_f32 Y; 82 | // 83 | arm_matrix_instance_f32 tmpP; 84 | arm_matrix_instance_f32 tmpX; 85 | arm_matrix_instance_f32 tmpYX; 86 | arm_matrix_instance_f32 tmpXY; 87 | arm_matrix_instance_f32 tmpXX; 88 | arm_matrix_instance_f32 tmpXXT; 89 | arm_matrix_instance_f32 tmpS; 90 | }EKF_Filter; 91 | 92 | void EKF_New(EKF_Filter* ekf); 93 | void EKF_Init(EKF_Filter* ekf, float32_t *q, float32_t *gyro); 94 | void EFK_Update(EKF_Filter* ekf, float32_t *q, float32_t *gyro, float32_t *accel, float32_t *mag, float32_t dt); 95 | void EKF_GetAngle(EKF_Filter* ekf, float32_t* rpy); 96 | 97 | inline void EKF_GetQ(EKF_Filter* efk, float32_t* Q) 98 | { 99 | Q[0] = efk->X_f32[0]; 100 | Q[1] = efk->X_f32[1]; 101 | Q[2] = efk->X_f32[2]; 102 | Q[3] = efk->X_f32[3]; 103 | } 104 | 105 | #endif 106 | -------------------------------------------------------------------------------- /Modules/AHRS/INS_EKF.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _INS_EKF_H_ 25 | #define _INS_EKF_H_ 26 | 27 | #include "Matrix.h" 28 | 29 | //16-state q0 q1 q2 q3 Pn Pe Alt Vn Ve Vd bwx bwy bwz bax bay baz 30 | #define INS_EKF_STATE_DIM 16 31 | 32 | //9-measurement mx my mz (3D magnetometer) Pn Pe Alt Vn Ve Vd 33 | //unit vector pointing to MagNorth in body coords 34 | //north pos, east pos, altitude 35 | //north vel, east vel, down velocity 36 | #define INS_EKF_MEASUREMENT_DIM 9 37 | 38 | #define INS_EKF_HALFPI 1.5707963267948966192313216916398f 39 | #define INS_EKF_PI 3.1415926535897932384626433832795f 40 | #define INS_EKF_TWOPI 6.283185307179586476925286766559f 41 | #define INS_EKF_TODEG(x) ((x) * 57.2957796f) 42 | 43 | typedef struct INS_EKF_FILTER_T{ 44 | //state covariance 45 | float32_t P_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 46 | float32_t PX_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 47 | float32_t PHT_f32[INS_EKF_STATE_DIM * INS_EKF_MEASUREMENT_DIM]; 48 | 49 | float32_t Q_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 50 | float32_t R_f32[INS_EKF_MEASUREMENT_DIM * INS_EKF_MEASUREMENT_DIM]; 51 | 52 | float32_t K_f32[INS_EKF_STATE_DIM * INS_EKF_MEASUREMENT_DIM]; 53 | float32_t KH_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 54 | float32_t KHP_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 55 | 56 | float32_t KY_f32[INS_EKF_STATE_DIM]; 57 | 58 | float32_t F_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 59 | float32_t FT_f32[INS_EKF_STATE_DIM * INS_EKF_STATE_DIM]; 60 | //The H matrix maps the measurement to the states 61 | float32_t H_f32[INS_EKF_MEASUREMENT_DIM * INS_EKF_STATE_DIM]; 62 | float32_t HT_f32[INS_EKF_STATE_DIM * INS_EKF_MEASUREMENT_DIM]; 63 | float32_t HP_f32[INS_EKF_MEASUREMENT_DIM * INS_EKF_STATE_DIM]; 64 | 65 | float32_t S_f32[INS_EKF_MEASUREMENT_DIM * INS_EKF_MEASUREMENT_DIM]; 66 | float32_t SI_f32[INS_EKF_MEASUREMENT_DIM * INS_EKF_MEASUREMENT_DIM]; 67 | //state vector 68 | float32_t X_f32[INS_EKF_STATE_DIM]; 69 | //measurement vector 70 | float32_t Y_f32[INS_EKF_MEASUREMENT_DIM]; 71 | 72 | arm_matrix_instance_f32 P; 73 | arm_matrix_instance_f32 PX; 74 | arm_matrix_instance_f32 PHT; 75 | arm_matrix_instance_f32 Q; 76 | arm_matrix_instance_f32 R; 77 | arm_matrix_instance_f32 K; 78 | arm_matrix_instance_f32 KH; 79 | arm_matrix_instance_f32 KHP; 80 | arm_matrix_instance_f32 KY; 81 | arm_matrix_instance_f32 F; 82 | arm_matrix_instance_f32 FT; 83 | arm_matrix_instance_f32 H; 84 | arm_matrix_instance_f32 HT; 85 | arm_matrix_instance_f32 HP; 86 | arm_matrix_instance_f32 S; 87 | arm_matrix_instance_f32 SI; 88 | 89 | arm_matrix_instance_f32 X; 90 | arm_matrix_instance_f32 Y; 91 | 92 | float32_t declination; 93 | float32_t gravity; //m/s^2 94 | }INS_EKF_Filter; 95 | 96 | void INS_EKF_New(INS_EKF_Filter* ins); 97 | void INS_EKF_Init(INS_EKF_Filter* ins, float32_t *p, float32_t *v, float32_t *accel, float32_t *mag); 98 | void INS_EFK_Update(INS_EKF_Filter* ins, float32_t *mag, float32_t *p, float32_t *v, float32_t *gyro, float32_t *accel, float32_t dt); 99 | void INS_EKF_GetAngle(INS_EKF_Filter* ins, float32_t* rpy); 100 | 101 | #endif 102 | -------------------------------------------------------------------------------- /Modules/AHRS/Quaternion.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _QUATERNION_H_ 25 | #define _QUATERNION_H_ 26 | 27 | #include "FastMath.h" 28 | 29 | inline void Quaternion_Add(float *r, float *a, float *b) 30 | { 31 | r[0] = a[0] + b[0]; 32 | r[1] = a[1] + b[1]; 33 | r[2] = a[2] + b[2]; 34 | r[3] = a[3] + b[3]; 35 | } 36 | 37 | inline void Quaternion_Sub(float *r, float *a, float *b) 38 | { 39 | r[0] = a[0] - b[0]; 40 | r[1] = a[1] - b[1]; 41 | r[2] = a[2] - b[2]; 42 | r[3] = a[3] - b[3]; 43 | } 44 | 45 | inline void Quaternion_Multiply(float *r, float *a, float *b) 46 | { 47 | r[0] = a[0] * b[0] - a[1] * b[1] - a[2] * b[2] - a[3] * b[3]; 48 | r[1] = a[0] * b[1] + a[1] * b[0] + a[2] * b[3] - a[3] * b[2]; 49 | r[2] = a[0] * b[2] - a[1] * b[3] + a[2] * b[0] + a[3] * b[1]; 50 | r[3] = a[0] * b[3] + a[1] * b[2] - a[2] * b[1] + a[3] * b[0]; 51 | } 52 | 53 | inline void Quaternion_Conjugate(float *r, float *a) 54 | { 55 | r[0] = a[0]; 56 | r[1] = -a[1]; 57 | r[2] = -a[2]; 58 | r[3] = -a[3]; 59 | } 60 | 61 | inline void Quaternion_Scalar(float *r, float *q, float scalar) 62 | { 63 | r[0] = q[0] * scalar; 64 | r[1] = q[1] * scalar; 65 | r[2] = q[2] * scalar; 66 | r[3] = q[3] * scalar; 67 | } 68 | 69 | void Quaternion_Normalize(float *q); 70 | void Quaternion_FromEuler(float *q, float *rpy); 71 | void Quaternion_ToEuler(float *q, float* rpy); 72 | void Quaternion_FromRotationMatrix(float *R, float *Q); 73 | void Quaternion_RungeKutta4(float *q, float *w, float dt, int normalize); 74 | void Quaternion_From6AxisData(float* q, float *accel, float *mag); 75 | 76 | #endif 77 | -------------------------------------------------------------------------------- /Modules/AHRS/UKF.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _UKF_H 25 | #define _UKF_H 26 | 27 | #include "Matrix.h" 28 | 29 | //7-state q0 q1 q2 q3 wx wy wz 30 | #define UKF_STATE_DIM 7 31 | //13-measurement q0 q1 q2 q3 ax ay az wx wy wz mx my mz 32 | #define UKF_MEASUREMENT_DIM 13 33 | 34 | #define UKF_SP_POINTS 15//(2 * UKF_STATE_DIM + 1) 35 | 36 | #define UKF_HALFPI 1.5707963267948966192313216916398f 37 | #define UKF_PI 3.1415926535897932384626433832795f 38 | #define UKF_TWOPI 6.283185307179586476925286766559f 39 | #define UKF_TODEG(x) ((x) * 57.2957796f) 40 | 41 | typedef struct UKF_FILTER_T{ 42 | //scaling factor 43 | float32_t gamma; 44 | //weights for means 45 | float32_t Wm0, Wmi; 46 | //weights for covariance 47 | float32_t Wc_f32[UKF_SP_POINTS * UKF_SP_POINTS]; 48 | //state covariance 49 | float32_t P_f32[UKF_STATE_DIM * UKF_STATE_DIM]; 50 | float32_t PX_f32[UKF_STATE_DIM * UKF_STATE_DIM]; 51 | float32_t PY_f32[UKF_MEASUREMENT_DIM * UKF_MEASUREMENT_DIM]; 52 | float32_t tmpPY_f32[UKF_MEASUREMENT_DIM * UKF_MEASUREMENT_DIM]; 53 | float32_t PXY_f32[UKF_STATE_DIM * UKF_MEASUREMENT_DIM]; 54 | float32_t PXYT_f32[UKF_MEASUREMENT_DIM * UKF_STATE_DIM]; 55 | float32_t Q_f32[UKF_STATE_DIM * UKF_STATE_DIM]; 56 | float32_t R_f32[UKF_MEASUREMENT_DIM * UKF_MEASUREMENT_DIM]; 57 | //Sigma points 58 | float32_t XSP_f32[UKF_STATE_DIM * UKF_SP_POINTS]; 59 | float32_t tmpXSP_f32[UKF_STATE_DIM * UKF_SP_POINTS]; 60 | float32_t tmpXSPT_f32[UKF_SP_POINTS * UKF_STATE_DIM]; 61 | float32_t tmpWcXSP_f32[UKF_STATE_DIM * UKF_SP_POINTS]; 62 | float32_t tmpWcYSP_f32[UKF_MEASUREMENT_DIM * UKF_SP_POINTS]; 63 | float32_t YSP_f32[UKF_MEASUREMENT_DIM * UKF_SP_POINTS]; 64 | float32_t tmpYSP_f32[UKF_MEASUREMENT_DIM * UKF_SP_POINTS]; 65 | float32_t tmpYSPT_f32[UKF_SP_POINTS * UKF_MEASUREMENT_DIM]; 66 | //Kalman gain 67 | float32_t K_f32[UKF_STATE_DIM * UKF_MEASUREMENT_DIM]; 68 | float32_t KT_f32[UKF_MEASUREMENT_DIM * UKF_STATE_DIM]; 69 | //state vector 70 | float32_t X_f32[UKF_STATE_DIM]; 71 | float32_t tmpX_f32[UKF_STATE_DIM]; 72 | //measurement vector 73 | float32_t Y_f32[UKF_MEASUREMENT_DIM]; 74 | float32_t tmpY_f32[UKF_MEASUREMENT_DIM]; 75 | // 76 | arm_matrix_instance_f32 Wc; 77 | arm_matrix_instance_f32 P; 78 | arm_matrix_instance_f32 PX; 79 | arm_matrix_instance_f32 PY; 80 | arm_matrix_instance_f32 tmpPY; 81 | arm_matrix_instance_f32 PXY; 82 | arm_matrix_instance_f32 PXYT; 83 | arm_matrix_instance_f32 Q; 84 | arm_matrix_instance_f32 R; 85 | // 86 | arm_matrix_instance_f32 XSP; 87 | arm_matrix_instance_f32 tmpXSP; 88 | arm_matrix_instance_f32 tmpXSPT; 89 | arm_matrix_instance_f32 tmpWcXSP; 90 | arm_matrix_instance_f32 tmpWcYSP; 91 | arm_matrix_instance_f32 YSP; 92 | arm_matrix_instance_f32 tmpYSP; 93 | arm_matrix_instance_f32 tmpYSPT; 94 | // 95 | arm_matrix_instance_f32 K; 96 | arm_matrix_instance_f32 KT; 97 | // 98 | arm_matrix_instance_f32 X; 99 | arm_matrix_instance_f32 tmpX; 100 | arm_matrix_instance_f32 Y; 101 | arm_matrix_instance_f32 tmpY; 102 | }UKF_Filter; 103 | 104 | void UKF_New(UKF_Filter* UKF); 105 | void UKF_Init(UKF_Filter* UKF, float32_t *q, float32_t *gyro); 106 | void UKF_Update(UKF_Filter* UKF, float32_t *q, float32_t *gyro, float32_t *accel, float32_t *mag, float32_t dt); 107 | void UKF_GetAngle(UKF_Filter* UKF, float32_t* rpy); 108 | 109 | inline void UKF_GetQ(UKF_Filter* ukf, float32_t* Q) 110 | { 111 | Q[0] = ukf->X_f32[0]; 112 | Q[1] = ukf->X_f32[1]; 113 | Q[2] = ukf->X_f32[2]; 114 | Q[3] = ukf->X_f32[3]; 115 | } 116 | 117 | #endif 118 | -------------------------------------------------------------------------------- /Modules/AHRS/miniAHRS/miniAHRS.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef MINIAHRS_H_ 25 | #define MINIAHRS_H_ 26 | ////////////////////////////////////////////////////////////////////////// 27 | // 28 | #define EKF_STATE_DIM 7 //q0 q1 q2 q3 wxb wyb wzb 29 | #define EKF_MEASUREMENT_DIM 6 //ax ay az and mx my mz 30 | 31 | #define EKF_HALFPI 1.5707963267948966192313216916398f 32 | #define EKF_PI 3.1415926535897932384626433832795f 33 | #define EKF_TWOPI 6.283185307179586476925286766559f 34 | #define EKF_TODEG(x) ((x) * 57.2957796f) 35 | 36 | void EKF_AHRSInit(float *accel, float *mag); 37 | void EKF_AHRSUpdate(float *gyro, float *accel, float *mag, float dt); 38 | void EKF_AHRSGetAngle(float* rpy); 39 | 40 | void EKF_AHRSGetQ(float* Q); 41 | 42 | #endif 43 | -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/FP/FP_Math.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _FP_FASTMATH_H_ 25 | #define _FP_FASTMATH_H_ 26 | 27 | #define FIXED_POINT 28 | #define PRECISION 16 29 | 30 | #define OPTIMIZE_SDIV 31 | 32 | typedef int Q16; 33 | typedef int int32_t; 34 | typedef unsigned int uint32_t; 35 | typedef unsigned char uint8_t; 36 | typedef unsigned short uint16_t; 37 | typedef signed __int64 int64_t; 38 | typedef unsigned __int64 uint64_t; 39 | 40 | #define Q16_One 65536 41 | 42 | ////////////////////////////////////////////////////////////////////////// 43 | //S16.16 44 | #define FP_ADDS(a, b) ((a) + (b)) 45 | #define FP_SUBS(a, b) ((a) - (b)) 46 | 47 | #define FP_SMUL_FRAC(a, b, frac) \ 48 | ((int32_t)((int64_t)(a)*(int64_t)(b) >> (frac))) 49 | 50 | #define FP_UMUL_FRAC(a, b, frac) \ 51 | ((uint32_t)((uint64_t)(a)*(uint64_t)(b) >> (frac))) 52 | 53 | #define FP_SMUL(a, b) \ 54 | ((int32_t)((int64_t)(a)*(int64_t)(b) >> 16)) 55 | 56 | #define FP_UMUL(a, b) \ 57 | ((uint32_t)((uint64_t)(a)*(uint64_t)(b) >> 16)) 58 | 59 | Q16 FP_SDIV(Q16 a, Q16 b); 60 | 61 | ////////////////////////////////////////////////////////////////////////// 62 | #define FP_ISQRT_UPDATE(est, mant2) \ 63 | (((est) + ((est) >> 1)) - \ 64 | FP_UMUL_FRAC(FP_UMUL_FRAC(mant2, est, 31), \ 65 | FP_UMUL_FRAC(est, est, 31), 31)) 66 | 67 | Q16 FT_Q16(float f); 68 | 69 | Q16 FP_Sqrt(Q16 xval, uint32_t frac); 70 | Q16 FP_SqrtI(Q16 xval, int32_t frac); 71 | 72 | __inline float Q16_FT(Q16 x) 73 | { 74 | return ((float)x) / 65536.0f; 75 | } 76 | ////////////////////////////////////////////////////////////////////////// 77 | //translate from google's skia fixed-point dsp Library. 78 | // 79 | #define TO_FLOAT_DEGREE(x) (((float)(x)) * 0.000874264215087890625f) 80 | #define Q16_TWOPI 411775 81 | #define Q16_PI 205887 82 | #define Q16_HALFPI 102944 83 | 84 | Q16 FP_FastAsin(Q16 a); 85 | Q16 FP_FastAtan2(Q16 y, Q16 x); 86 | 87 | #endif 88 | -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/FP/FP_Matrix.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _FP_MAXTRIX_H_ 25 | #define _FP_MAXTRIX_H_ 26 | 27 | #include "FP_Math.h" 28 | ////////////////////////////////////////////////////////////////////////// 29 | // 30 | void FP_Matrix_Copy(Q16 *pSrc, int numRows, int numCols, Q16 *pDst); 31 | int FP_Maxtrix_Add(Q16 *pSrcA, unsigned short numRows, unsigned short numCols, Q16 *pSrcB, Q16 *pDst); 32 | int FP_Maxtrix_Sub(Q16 *pSrcA, unsigned short numRows, unsigned short numCols, Q16 *pSrcB, Q16 *pDst); 33 | int FP_Matrix_Multiply(Q16 *A, int nrows, int ncols, Q16 *B, int mcols, Q16 *C); 34 | void FP_Matrix_Multiply_With_Transpose(Q16 *A, int nrows, int ncols, Q16 *B, int mrows, Q16 *C); 35 | int FP_Matrix_Inverse(Q16* pSrc, unsigned short n, Q16* pDst); 36 | #endif 37 | -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/FP/FP_miniIMU.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _FP_MINIIMU_H_ 25 | #define _FP_MINIIMU_H_ 26 | 27 | ////////////////////////////////////////////////////////////////////////// 28 | //S16.16 29 | //#define FP_EKF_STATE_DIM 4 //q0 q1 q2 q3 30 | #define FP_EKF_STATE_DIM 7 //q0 q1 q2 q3 wxb wyb wzb 31 | #define FP_EKF_MEASUREMENT_DIM 3 //ax ay az 32 | 33 | void FP_EKF_IMUInit(float *accel, float *gyro); 34 | void FP_EKF_IMUUpdate(float *gyro, float *accel, float dt); 35 | void FP_EKF_IMUGetAngle(float* rpy); 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/Usage.txt: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | ////////////////////////////////////////////////////////////////////////// 25 | //setp 1: 26 | Decide how many states do you want to use. 27 | Look into the filename of "miniIMU.h" 28 | 29 | either uncomment #define EKF_STATE_DIM 4 30 | or uncomment #define EKF_STATE_DIM 7 on your own, 31 | by default is "define EKF_STATE_DIM 7" 32 | 33 | ////////////////////////////////////////////////////////////////////////// 34 | //setp 2: 35 | // 36 | using the struct as below,In the main loop of the program 37 | ...... 38 | if EKF is not initialization 39 | EKF_IMUInit(accel, gyro); 40 | else 41 | EKF_IMUUpdate(gyro, accel, dt); 42 | ...... 43 | EKF_IMUGetAngle(rpy); 44 | 45 | 46 | Enjoy it! -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/miniIMU.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef MINIIMU_H_ 25 | #define MINIIMU_H_ 26 | ////////////////////////////////////////////////////////////////////////// 27 | // 28 | //#define EKF_STATE_DIM 4 //q0 q1 q2 q3 29 | #define EKF_STATE_DIM 7 //q0 q1 q2 q3 wxb wyb wzb 30 | #define EKF_MEASUREMENT_DIM 3 //ax ay az 31 | 32 | #define EKF_HALFPI 1.5707963267948966192313216916398f 33 | #define EKF_PI 3.1415926535897932384626433832795f 34 | #define EKF_TWOPI 6.283185307179586476925286766559f 35 | #define EKF_TODEG(x) ((x) * 57.2957796f) 36 | 37 | void EKF_IMUInit(float *accel, float *gyro); 38 | void EKF_IMUUpdate(float *gyro, float *accel, float dt); 39 | void EKF_IMUGetAngle(float* rpy); 40 | 41 | void EKF_IMUGetQ(float *Q); 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /Modules/AHRS/miniIMU/miniMatrix.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _MAXTRIX_H_ 25 | #define _MAXTRIX_H_ 26 | 27 | #include "FastMath.h" 28 | 29 | ////////////////////////////////////////////////////////////////////////// 30 | // 31 | 32 | void Matrix_Zero(float *A, unsigned short numRows, unsigned short numCols); 33 | void Matrix_Copy(float *pSrc, unsigned short numRows, unsigned short numCols, float *pDst); 34 | int Maxtrix_Add(float *pSrcA, unsigned short numRows, unsigned short numCols, float *pSrcB, float *pDst); 35 | int Maxtrix_Sub(float *pSrcA, unsigned short numRows, unsigned short numCols, float *pSrcB, float *pDst); 36 | int Matrix_Multiply(float* pSrcA, unsigned short numRowsA, unsigned short numColsA, float* pSrcB, unsigned short numColsB, float* pDst); 37 | void Matrix_Multiply_With_Transpose(float *A, unsigned short nrows, unsigned short ncols, float *B, unsigned short mrows, float *C); 38 | void Maxtrix_Transpose(float *pSrc, unsigned short nRows, unsigned short nCols, float *pDst); 39 | int Matrix_Inverse(float* pDst, unsigned short n, float * pSrc); 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /Modules/Matrix/DoubleMatrix.c: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #include "DoubleMatrix.h" 25 | #include "FastMath.h" 26 | 27 | -------------------------------------------------------------------------------- /Modules/Matrix/DoubleMatrix.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _DOUBLEMATRIX_H_ 25 | #define _DOUBLEMATRIX_H_ 26 | 27 | #include "Double.h" 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /Modules/Matrix/Matrix.h: -------------------------------------------------------------------------------- 1 | /* 2 | The MIT License (MIT) 3 | 4 | Copyright (c) 2015-? suhetao 5 | 6 | Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | this software and associated documentation files (the "Software"), to deal in 8 | the Software without restriction, including without limitation the rights to 9 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | the Software, and to permit persons to whom the Software is furnished to do so, 11 | subject to the following conditions: 12 | 13 | The above copyright notice and this permission notice shall be included in all 14 | copies or substantial portions of the Software. 15 | 16 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | */ 23 | 24 | #ifndef _MATRIX_H_ 25 | #define _MATRIX_H_ 26 | 27 | #include "arm_math.h" 28 | 29 | void arm_mat_zero_f32(arm_matrix_instance_f32* s); 30 | arm_status mat_identity(float32_t *pData, uint16_t numRows, uint16_t numCols, float32_t value); 31 | arm_status arm_mat_identity_f32(arm_matrix_instance_f32* s, float32_t value); 32 | arm_status arm_mat_fill_f32(arm_matrix_instance_f32* s, float32_t *pData, uint32_t blockSize); 33 | arm_status arm_mat_chol_f32(arm_matrix_instance_f32* s); 34 | arm_status arm_mat_remainlower_f32(arm_matrix_instance_f32* s); 35 | 36 | void arm_mat_getsubmatrix_f32(arm_matrix_instance_f32* s, arm_matrix_instance_f32 *a, int row, int col); 37 | void arm_mat_setsubmatrix_f32(arm_matrix_instance_f32* a, arm_matrix_instance_f32 *s, int row, int col); 38 | 39 | void arm_mat_getcolumn_f32(arm_matrix_instance_f32* s, float32_t *x, uint32_t col); 40 | void arm_mat_setcolumn_f32(arm_matrix_instance_f32* s, float32_t *x, uint32_t col); 41 | void arm_mat_cumsum_f32(arm_matrix_instance_f32* s, float32_t *tmp, float32_t *x); 42 | int arm_mat_qr_decompositionT_f32(arm_matrix_instance_f32 *A, arm_matrix_instance_f32 *R); 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /Modules/MavLink/checksum.h: -------------------------------------------------------------------------------- 1 | #ifdef __cplusplus 2 | extern "C" { 3 | #endif 4 | 5 | #ifndef _CHECKSUM_H_ 6 | #define _CHECKSUM_H_ 7 | 8 | // Visual Studio versions before 2010 don't have stdint.h, so we just error out. 9 | #if (defined _MSC_VER) && (_MSC_VER < 1600) 10 | #error "The C-MAVLink implementation requires Visual Studio 2010 or greater" 11 | #endif 12 | 13 | #include 14 | 15 | /** 16 | * 17 | * CALCULATE THE CHECKSUM 18 | * 19 | */ 20 | 21 | #define X25_INIT_CRC 0xffff 22 | #define X25_VALIDATE_CRC 0xf0b8 23 | 24 | #ifndef HAVE_CRC_ACCUMULATE 25 | /** 26 | * @brief Accumulate the X.25 CRC by adding one char at a time. 27 | * 28 | * The checksum function adds the hash of one char at a time to the 29 | * 16 bit checksum (uint16_t). 30 | * 31 | * @param data new char to hash 32 | * @param crcAccum the already accumulated checksum 33 | **/ 34 | static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) 35 | { 36 | /*Accumulate one byte of data into the CRC*/ 37 | uint8_t tmp; 38 | 39 | tmp = data ^ (uint8_t)(*crcAccum &0xff); 40 | tmp ^= (tmp<<4); 41 | *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); 42 | } 43 | #endif 44 | 45 | 46 | /** 47 | * @brief Initiliaze the buffer for the X.25 CRC 48 | * 49 | * @param crcAccum the 16 bit X.25 CRC 50 | */ 51 | static inline void crc_init(uint16_t* crcAccum) 52 | { 53 | *crcAccum = X25_INIT_CRC; 54 | } 55 | 56 | 57 | /** 58 | * @brief Calculates the X.25 checksum on a byte buffer 59 | * 60 | * @param pBuffer buffer containing the byte array to hash 61 | * @param length length of the byte array 62 | * @return the checksum over the buffer bytes 63 | **/ 64 | static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) 65 | { 66 | uint16_t crcTmp; 67 | crc_init(&crcTmp); 68 | while (length--) { 69 | crc_accumulate(*pBuffer++, &crcTmp); 70 | } 71 | return crcTmp; 72 | } 73 | 74 | 75 | /** 76 | * @brief Accumulate the X.25 CRC by adding an array of bytes 77 | * 78 | * The checksum function adds the hash of one char at a time to the 79 | * 16 bit checksum (uint16_t). 80 | * 81 | * @param data new bytes to hash 82 | * @param crcAccum the already accumulated checksum 83 | **/ 84 | static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) 85 | { 86 | const uint8_t *p = (const uint8_t *)pBuffer; 87 | while (length--) { 88 | crc_accumulate(*p++, crcAccum); 89 | } 90 | } 91 | 92 | #endif /* _CHECKSUM_H_ */ 93 | 94 | #ifdef __cplusplus 95 | } 96 | #endif 97 | -------------------------------------------------------------------------------- /Modules/MavLink/common/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from common.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_IDX 1 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 254 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 0 29 | #endif 30 | 31 | #include "version.h" 32 | #include "common.h" 33 | 34 | void Mavlink_Task (void const * argument); 35 | 36 | #endif // MAVLINK_H 37 | -------------------------------------------------------------------------------- /Modules/MavLink/common/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from common.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Mon Jun 26 2017" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Firmware 2 | 飞控固件 3 | -------------------------------------------------------------------------------- /Src/fatfs.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file fatfs.c 4 | * @brief Code for fatfs applications 5 | ****************************************************************************** 6 | * 7 | * Copyright (c) 2017 STMicroelectronics International N.V. 8 | * All rights reserved. 9 | * 10 | * Redistribution and use in source and binary forms, with or without 11 | * modification, are permitted, provided that the following conditions are met: 12 | * 13 | * 1. Redistribution of source code must retain the above copyright notice, 14 | * this list of conditions and the following disclaimer. 15 | * 2. Redistributions in binary form must reproduce the above copyright notice, 16 | * this list of conditions and the following disclaimer in the documentation 17 | * and/or other materials provided with the distribution. 18 | * 3. Neither the name of STMicroelectronics nor the names of other 19 | * contributors to this software may be used to endorse or promote products 20 | * derived from this software without specific written permission. 21 | * 4. This software, including modifications and/or derivative works of this 22 | * software, must execute solely and exclusively on microcontroller or 23 | * microprocessor devices manufactured by or for STMicroelectronics. 24 | * 5. Redistribution and use of this software other than as permitted under 25 | * this license is void and will automatically terminate your rights under 26 | * this license. 27 | * 28 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 29 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 30 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 31 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 32 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 33 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 35 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 36 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 37 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 38 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 39 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 40 | * 41 | ****************************************************************************** 42 | */ 43 | 44 | #include "fatfs.h" 45 | 46 | uint8_t retSD; /* Return value for SD */ 47 | char SD_Path[4]; /* SD logical drive path */ 48 | 49 | /* USER CODE BEGIN Variables */ 50 | 51 | /* USER CODE END Variables */ 52 | 53 | void MX_FATFS_Init(void) 54 | { 55 | /*## FatFS: Link the SD driver ###########################*/ 56 | retSD = FATFS_LinkDriver(&SD_Driver, SD_Path); 57 | 58 | /* USER CODE BEGIN Init */ 59 | /* additional user code for init */ 60 | /* USER CODE END Init */ 61 | } 62 | 63 | /** 64 | * @brief Gets Time from RTC 65 | * @param None 66 | * @retval Time in DWORD 67 | */ 68 | DWORD get_fattime(void) 69 | { 70 | /* USER CODE BEGIN get_fattime */ 71 | return 0; 72 | /* USER CODE END get_fattime */ 73 | } 74 | 75 | /* USER CODE BEGIN Application */ 76 | 77 | /* USER CODE END Application */ 78 | 79 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 80 | -------------------------------------------------------------------------------- /Src/lwip.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : LWIP.c 4 | * Description : This file provides initialization code for LWIP 5 | * middleWare. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | /* Includes ------------------------------------------------------------------*/ 46 | #include "lwip.h" 47 | #include "lwip/init.h" 48 | #include "lwip/netif.h" 49 | 50 | /* USER CODE BEGIN 0 */ 51 | 52 | /* USER CODE END 0 */ 53 | 54 | /* ETH Variables initialization ----------------------------------------------*/ 55 | void Error_Handler(void); 56 | 57 | /* USER CODE BEGIN 1 */ 58 | 59 | /* USER CODE END 1 */ 60 | 61 | /* Variables Initialization */ 62 | struct netif gnetif; 63 | ip4_addr_t ipaddr; 64 | ip4_addr_t netmask; 65 | ip4_addr_t gw; 66 | 67 | /* USER CODE BEGIN 2 */ 68 | 69 | /* USER CODE END 2 */ 70 | 71 | /** 72 | * LwIP initialization function 73 | */ 74 | void MX_LWIP_Init(void) 75 | { 76 | /* Initilialize the LwIP stack with RTOS */ 77 | tcpip_init( NULL, NULL ); 78 | 79 | /* IP addresses initialization with DHCP (IPv4) */ 80 | ipaddr.addr = 0; 81 | netmask.addr = 0; 82 | gw.addr = 0; 83 | 84 | /* add the network interface (IPv4/IPv6) with RTOS */ 85 | netif_add(&gnetif, &ipaddr, &netmask, &gw, NULL, ðernetif_init, &tcpip_input); 86 | 87 | /* Registers the default network interface */ 88 | netif_set_default(&gnetif); 89 | 90 | if (netif_is_link_up(&gnetif)) 91 | { 92 | /* When the netif is fully configured this function must be called */ 93 | netif_set_up(&gnetif); 94 | } 95 | else 96 | { 97 | /* When the netif link is down this function must be called */ 98 | netif_set_down(&gnetif); 99 | } 100 | 101 | /* Start DHCP negotiation for a network interface (IPv4) */ 102 | dhcp_start(&gnetif); 103 | 104 | /* USER CODE BEGIN 3 */ 105 | 106 | /* USER CODE END 3 */ 107 | } 108 | /* USER CODE BEGIN 4 */ 109 | 110 | /* USER CODE END 4 */ 111 | 112 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 113 | -------------------------------------------------------------------------------- /Src/stm32f7xx_hal_msp.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * File Name : stm32f7xx_hal_msp.c 4 | * Description : This file provides code for the MSP Initialization 5 | * and de-Initialization codes. 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | /* Includes ------------------------------------------------------------------*/ 45 | #include "stm32f7xx_hal.h" 46 | 47 | extern void Error_Handler(void); 48 | /* USER CODE BEGIN 0 */ 49 | 50 | /* USER CODE END 0 */ 51 | /** 52 | * Initializes the Global MSP. 53 | */ 54 | void HAL_MspInit(void) 55 | { 56 | /* USER CODE BEGIN MspInit 0 */ 57 | 58 | /* USER CODE END MspInit 0 */ 59 | 60 | HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); 61 | 62 | /* System interrupt init*/ 63 | /* MemoryManagement_IRQn interrupt configuration */ 64 | HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); 65 | /* BusFault_IRQn interrupt configuration */ 66 | HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); 67 | /* UsageFault_IRQn interrupt configuration */ 68 | HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); 69 | /* SVCall_IRQn interrupt configuration */ 70 | HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); 71 | /* DebugMonitor_IRQn interrupt configuration */ 72 | HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); 73 | /* PendSV_IRQn interrupt configuration */ 74 | HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); 75 | /* SysTick_IRQn interrupt configuration */ 76 | HAL_NVIC_SetPriority(SysTick_IRQn, 15, 0); 77 | 78 | /* USER CODE BEGIN MspInit 1 */ 79 | 80 | /* USER CODE END MspInit 1 */ 81 | } 82 | 83 | /* USER CODE BEGIN 1 */ 84 | 85 | /* USER CODE END 1 */ 86 | 87 | /** 88 | * @} 89 | */ 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 96 | -------------------------------------------------------------------------------- /Src/usb_device.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : USB_DEVICE 4 | * @version : v1.0_Cube 5 | * @brief : This file implements the USB Device 6 | ****************************************************************************** 7 | * 8 | * Copyright (c) 2017 STMicroelectronics International N.V. 9 | * All rights reserved. 10 | * 11 | * Redistribution and use in source and binary forms, with or without 12 | * modification, are permitted, provided that the following conditions are met: 13 | * 14 | * 1. Redistribution of source code must retain the above copyright notice, 15 | * this list of conditions and the following disclaimer. 16 | * 2. Redistributions in binary form must reproduce the above copyright notice, 17 | * this list of conditions and the following disclaimer in the documentation 18 | * and/or other materials provided with the distribution. 19 | * 3. Neither the name of STMicroelectronics nor the names of other 20 | * contributors to this software may be used to endorse or promote products 21 | * derived from this software without specific written permission. 22 | * 4. This software, including modifications and/or derivative works of this 23 | * software, must execute solely and exclusively on microcontroller or 24 | * microprocessor devices manufactured by or for STMicroelectronics. 25 | * 5. Redistribution and use of this software other than as permitted under 26 | * this license is void and will automatically terminate your rights under 27 | * this license. 28 | * 29 | * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 30 | * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 32 | * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY 33 | * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 34 | * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 35 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 36 | * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 37 | * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 38 | * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING 39 | * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, 40 | * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 41 | * 42 | ****************************************************************************** 43 | */ 44 | 45 | /* Includes ------------------------------------------------------------------*/ 46 | 47 | #include "usb_device.h" 48 | #include "usbd_core.h" 49 | #include "usbd_desc.h" 50 | #include "usbd_cdc.h" 51 | #include "usbd_cdc_if.h" 52 | 53 | /* USB Device Core handle declaration */ 54 | USBD_HandleTypeDef hUsbDeviceFS; 55 | 56 | /* init function */ 57 | void MX_USB_DEVICE_Init(void) 58 | { 59 | /* Init Device Library,Add Supported Class and Start the library*/ 60 | USBD_Init(&hUsbDeviceFS, &FS_Desc, DEVICE_FS); 61 | 62 | USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC); 63 | 64 | USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS); 65 | 66 | USBD_Start(&hUsbDeviceFS); 67 | 68 | } 69 | /** 70 | * @} 71 | */ 72 | 73 | /** 74 | * @} 75 | */ 76 | 77 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 78 | --------------------------------------------------------------------------------